Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changes to build in Ubuntu 22.04/24.04 #2829

Draft
wants to merge 10 commits into
base: master
Choose a base branch
from
2 changes: 1 addition & 1 deletion checkerboard_detector/src/checkerboard_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ class CheckerboardDetector

srv = boost::make_shared <dynamic_reconfigure::Server<Config> > (_node);
typename dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (&CheckerboardDetector::configCallback, this, _1, _2);
boost::bind (&CheckerboardDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv->setCallback (f);

while(1) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ int main(int argc, char** argv)
message_filters::Synchronizer<SyncPolicy> sync(
SyncPolicy(1000),
detection1_sub, detection2_sub);
sync.registerCallback(boost::bind(&callback, _1, _2));
sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2));
ros::spin();
return 0;
}
4 changes: 2 additions & 2 deletions cr_capture/src/cr_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class CRCaptureNode {
CRCaptureNode () : nh_("~"), it_(nh_), sync_(5)
{
// Set up dynamic reconfiguration
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, _1, _2);
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2);
reconfigure_server_.setCallback(f);

// parameter
Expand Down Expand Up @@ -171,7 +171,7 @@ class CRCaptureNode {
info_sub_.subscribe(nh_, range_ns_ + "/camera_info", 1);

sync_.connectInput(image_conf_sub_, image_intent_sub_, image_depth_sub_, info_sub_);
sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, _1, _2, _3, _4));
sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
} else {
// not all subscribe
camera_sub_depth_ = it_.subscribeCamera(range_ns_ + "/image", 1, &CRCaptureNode::camerarangeCB, this);
Expand Down
4 changes: 2 additions & 2 deletions cr_capture/src/cr_node_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class CRCaptureSyncNode {
CRCaptureSyncNode () : nh_("~"), it_(nh_), sync_(30)
{
// Set up dynamic reconfiguration
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, _1, _2);
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2);
reconfigure_server_.setCallback(f);

// parameter
Expand Down Expand Up @@ -175,7 +175,7 @@ class CRCaptureSyncNode {
sync_.connectInput(image_sub_left_, info_sub_left_, image_sub_right_, info_sub_right_,
image_sub_confi_, image_sub_intent_, image_sub_depth_, info_sub_range_);

sync_.registerCallback(boost::bind(&CRCaptureSyncNode::imageCB, this, _1, _2, _3, _4, _5, _6, _7, _8));
sync_.registerCallback(boost::bind(&CRCaptureSyncNode::imageCB, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, _6, _7, _8));

// pull raw data service
nh_.param("pull_raw_data", pull_raw_data, false);
Expand Down
4 changes: 2 additions & 2 deletions imagesift/src/imagesift.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ namespace imagesift
_subMask.subscribe(*nh_, "mask", 1);
_sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
_sync->connectInput(_subImageWithMask, _subMask);
_sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2));
_sync->registerCallback(boost::bind(&SiftNode::imageCb, this, boost::placeholders::_1, boost::placeholders::_2));
}
_subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this);
}
Expand Down Expand Up @@ -248,5 +248,5 @@ namespace imagesift
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (imagesift::SiftNode, nodelet::Nodelet);
4 changes: 2 additions & 2 deletions jsk_libfreenect2/src/driver_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ namespace jsk_libfreenect2
glfwInit();
timer_ = getNodeHandle().createTimer(
ros::Duration(5.0),
boost::bind(&Driver::run, this, _1), true);
boost::bind(&Driver::run, this, boost::placeholders::_1), true);
}

void Driver::run(const ros::TimerEvent&) {
Expand Down Expand Up @@ -235,7 +235,7 @@ namespace jsk_libfreenect2

}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
typedef jsk_libfreenect2::Driver Driver;
PLUGINLIB_EXPORT_CLASS(Driver, nodelet::Nodelet);

1 change: 1 addition & 0 deletions jsk_pcl_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ endif()

find_package(catkin REQUIRED COMPONENTS
cv_bridge
diagnostic_updater
dynamic_reconfigure
eigen_conversions
# genmsg
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/include/jsk_pcl_ros/depth_image_creator.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <pcl_ros/pcl_nodelet.h>
#include <pcl_ros/transforms.h>

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <dynamic_reconfigure/server.h>

#include <pcl/range_image/range_image_planar.h>
Expand Down
1 change: 1 addition & 0 deletions jsk_pcl_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<!-- <exec_depend>pcl</exec_depend> -->
<build_depend>cv_bridge</build_depend>
<build_depend>diagnostic_updater</build_depend>
<build_depend>dynamic_reconfigure</build_depend>
<build_depend>image_geometry</build_depend>
<build_depend>image_transport</build_depend>
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/add_color_from_image_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace jsk_pcl_ros
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
sync_->connectInput(sub_cloud_, sub_image_, sub_info_);
sync_->registerCallback(boost::bind(&AddColorFromImage::addColor,
this, _1, _2, _3));
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}

void AddColorFromImage::unsubscribe()
Expand Down Expand Up @@ -134,5 +134,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet);
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ namespace jsk_pcl_ros
sub_image_.subscribe(*pnh_, "input/image", 1);
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
sync_->connectInput(sub_cloud_, sub_image_);
sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, _1, _2));
sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, boost::placeholders::_1, boost::placeholders::_2));
}

void AddColorFromImageToOrganized::unsubscribe()
Expand Down Expand Up @@ -130,5 +130,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImageToOrganized, nodelet::Nodelet);
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/attention_clipper_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -428,7 +428,7 @@ namespace jsk_pcl_ros
pcl::PointIndices non_nan_indices;
for (size_t j = 0; j < indices->indices.size(); j++) {
pcl::PointXYZ p = cloud->points[indices->indices[j]];
if (pcl_isfinite(p.x) && pcl_isfinite(p.y) && pcl_isfinite(p.z)) {
if (std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z)) {
non_nan_indices.indices.push_back(indices->indices[j]);
}
}
Expand Down Expand Up @@ -523,5 +523,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::AttentionClipper, nodelet::Nodelet);
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/bilateral_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ namespace jsk_pcl_ros
ConnectionBasedNodelet::onInit();
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
typename dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (&BilateralFilter::configCallback, this, _1, _2);
boost::bind (&BilateralFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
Expand Down Expand Up @@ -95,6 +95,6 @@ namespace jsk_pcl_ros

}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BilateralFilter,
nodelet::Nodelet);
6 changes: 3 additions & 3 deletions jsk_pcl_ros/src/border_estimator_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace jsk_pcl_ros
pnh_->param("model_type", model_type_, std::string("planar"));
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
typename dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (&BorderEstimator::configCallback, this, _1, _2);
boost::bind (&BorderEstimator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

pub_border_ = advertise<PCLIndicesMsg>(*pnh_, "output_border_indices", 1);
Expand Down Expand Up @@ -82,7 +82,7 @@ namespace jsk_pcl_ros
sub_camera_info_.subscribe(*pnh_, "input_camera_info", 1);
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
sync_->connectInput(sub_point_, sub_camera_info_);
sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, _1, _2));
sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, boost::placeholders::_1, boost::placeholders::_2));
}
else if (model_type_ == "laser") {
sub_ = pnh_->subscribe("input", 1, &BorderEstimator::estimate, this);
Expand Down Expand Up @@ -210,6 +210,6 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BorderEstimator,
nodelet::Nodelet);
8 changes: 4 additions & 4 deletions jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace jsk_pcl_ros
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (
&BoundingBoxFilter::configCallback, this, _1, _2);
&BoundingBoxFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

////////////////////////////////////////////////////////
Expand Down Expand Up @@ -82,9 +82,9 @@ namespace jsk_pcl_ros
sub_indices_.subscribe(*pnh_, "input_indices", 1);
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
sync_->connectInput(sub_box_, sub_indices_);
sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, _1, _2));
sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, boost::placeholders::_1, boost::placeholders::_2));
} else {
sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1));
sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, boost::placeholders::_1));
}
}

Expand Down Expand Up @@ -249,5 +249,5 @@ namespace jsk_pcl_ros

}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BoundingBoxFilter, nodelet::Nodelet);
2 changes: 1 addition & 1 deletion jsk_pcl_ros/src/boundingbox_occlusion_rejector_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -241,5 +241,5 @@ namespace jsk_pcl_ros

}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BoundingBoxOcclusionRejector, nodelet::Nodelet);
12 changes: 6 additions & 6 deletions jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,11 +117,11 @@ namespace jsk_pcl_ros
sub_disparity_);
sync_->registerCallback(boost::bind(&CaptureStereoSynchronizer::republish,
this,
_1,
_2,
_3,
_4,
_5,
boost::placeholders::_1,
boost::placeholders::_2,
boost::placeholders::_3,
boost::placeholders::_4,
boost::placeholders::_5,
_6,
_7));
}
Expand Down Expand Up @@ -166,5 +166,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::CaptureStereoSynchronizer, nodelet::Nodelet);
14 changes: 7 additions & 7 deletions jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@

#include "jsk_pcl_ros/cluster_point_indices_decomposer.h"
#include <cv_bridge/cv_bridge.h>
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
#include <pcl/filters/extract_indices.h>
#include <pcl/common/centroid.h>
#include <pcl/common/common.h>
Expand Down Expand Up @@ -120,7 +120,7 @@ namespace jsk_pcl_ros
// dynamic_reconfigure
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, _1, _2);
boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback(f);

negative_indices_pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "negative_indices", 1);
Expand Down Expand Up @@ -153,24 +153,24 @@ namespace jsk_pcl_ros
if (use_async_) {
async_align_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncAlignPolicy> >(queue_size_);
async_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_);
async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
}
else {
sync_align_ = boost::make_shared<message_filters::Synchronizer<SyncAlignPolicy> >(queue_size_);
sync_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_);
sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
}
}
else {
if (use_async_) {
async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
async_->connectInput(sub_input_, sub_target_);
async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2));
}
else {
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
sync_->connectInput(sub_input_, sub_target_);
sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2));
}
}
}
Expand Down Expand Up @@ -575,7 +575,7 @@ namespace jsk_pcl_ros
double xwidth = maxpt[0] - minpt[0];
double ywidth = maxpt[1] - minpt[1];
double zwidth = maxpt[2] - minpt[2];
if (!pcl_isfinite(xwidth) || !pcl_isfinite(ywidth) || !pcl_isfinite(zwidth))
if (!std::isfinite(xwidth) || !std::isfinite(ywidth) || !std::isfinite(zwidth))
{
// all points in cloud are nan or its size is 0
xwidth = ywidth = zwidth = 0;
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros/src/collision_detector_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,5 +183,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::CollisionDetector, nodelet::Nodelet);
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace jsk_pcl_ros
ConnectionBasedNodelet::onInit();
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f=
boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, _1, _2);
boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);
pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
onInitPostProcess();
Expand Down Expand Up @@ -118,5 +118,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ColorBasedRegionGrowingSegmentation, nodelet::Nodelet);
6 changes: 3 additions & 3 deletions jsk_pcl_ros/src/color_filter_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include "jsk_pcl_ros/color_filter.h"

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>

namespace jsk_pcl_ros
{
Expand Down Expand Up @@ -342,7 +342,7 @@ namespace jsk_pcl_ros

srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
typename dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind (&ColorFilter::configCallback, this, _1, _2);
boost::bind (&ColorFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

onInitPostProcess();
Expand All @@ -356,7 +356,7 @@ namespace jsk_pcl_ros
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
sub_indices_.subscribe(*pnh_, "indices", 1);
sync_->connectInput(sub_input_, sub_indices_);
sync_->registerCallback(boost::bind(&ColorFilter::filter, this, _1, _2));
sync_->registerCallback(boost::bind(&ColorFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2));
//sub_input_ = pnh_->subscribe("input", 1, &RGBColorFilter::filter, this);
}
else {
Expand Down
4 changes: 2 additions & 2 deletions jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ namespace jsk_pcl_ros

srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
dynamic_reconfigure::Server<Config>::CallbackType f =
boost::bind(&ColorHistogramClassifier::configCallback, this, _1, _2);
boost::bind(&ColorHistogramClassifier::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback(f);
pub_class_ = advertise<jsk_recognition_msgs::ClassificationResult>(*pnh_, "output", 1);
onInitPostProcess();
Expand Down Expand Up @@ -208,5 +208,5 @@ namespace jsk_pcl_ros
}
}

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorHistogramClassifier, nodelet::Nodelet);
Loading
Loading