From fde5ccb40a5b322f9c6a8e7dda004d05fc08468d Mon Sep 17 00:00:00 2001 From: Jochen Sprickerhof Date: Tue, 15 Dec 2020 13:21:03 +0100 Subject: [PATCH 1/3] Switch to new boost/bind/bind.hpp --- pcl_ros/src/pcl_ros/features/feature.cpp | 24 +++++++++---------- pcl_ros/src/pcl_ros/filters/crop_box.cpp | 2 +- .../src/pcl_ros/filters/extract_indices.cpp | 2 +- pcl_ros/src/pcl_ros/filters/filter.cpp | 8 +++---- pcl_ros/src/pcl_ros/filters/passthrough.cpp | 2 +- .../src/pcl_ros/filters/project_inliers.cpp | 4 ++-- .../filters/radius_outlier_removal.cpp | 2 +- .../filters/statistical_outlier_removal.cpp | 2 +- pcl_ros/src/pcl_ros/filters/voxel_grid.cpp | 2 +- pcl_ros/src/pcl_ros/io/concatenate_data.cpp | 6 ++--- .../pcl_ros/segmentation/extract_clusters.cpp | 8 +++---- .../extract_polygonal_prism_data.cpp | 8 +++---- .../pcl_ros/segmentation/sac_segmentation.cpp | 22 ++++++++--------- .../segmentation/segment_differences.cpp | 6 ++--- pcl_ros/src/pcl_ros/surface/convex_hull.cpp | 6 ++--- .../pcl_ros/surface/moving_least_squares.cpp | 8 +++---- .../src/test/test_tf_message_filter_pcl.cpp | 24 +++++++++---------- 17 files changed, 68 insertions(+), 68 deletions(-) diff --git a/pcl_ros/src/pcl_ros/features/feature.cpp b/pcl_ros/src/pcl_ros/features/feature.cpp index cee3dbc28..c36bd499f 100644 --- a/pcl_ros/src/pcl_ros/features/feature.cpp +++ b/pcl_ros/src/pcl_ros/features/feature.cpp @@ -80,7 +80,7 @@ pcl_ros::Feature::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&Feature::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&Feature::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n" @@ -124,7 +124,7 @@ pcl_ros::Feature::subscribe () } else // Use only indices { - sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1)); // surface not enabled, connect the input-indices duo and register if (approximate_sync_) sync_input_surface_indices_a_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_); @@ -134,7 +134,7 @@ pcl_ros::Feature::subscribe () } else // Use only surface { - sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1)); // indices not enabled, connect the input-surface duo and register sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_); if (approximate_sync_) @@ -144,13 +144,13 @@ pcl_ros::Feature::subscribe () } // Register callbacks if (approximate_sync_) - sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3)); + sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); else - sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3)); + sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, _1, PointCloudInConstPtr (), PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, PointCloudInConstPtr (), PointIndicesConstPtr ())); } //////////////////////////////////////////////////////////////////////////////////////////// @@ -300,7 +300,7 @@ pcl_ros::FeatureFromNormals::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n" @@ -345,7 +345,7 @@ pcl_ros::FeatureFromNormals::subscribe () } else // Use only indices { - sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1)); if (approximate_sync_) // surface not enabled, connect the input-indices duo and register sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_); @@ -359,7 +359,7 @@ pcl_ros::FeatureFromNormals::subscribe () // indices not enabled, connect the input-surface duo and register sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_); - sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1)); if (approximate_sync_) sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_); else @@ -368,7 +368,7 @@ pcl_ros::FeatureFromNormals::subscribe () } else { - sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1)); if (approximate_sync_) sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_); @@ -378,9 +378,9 @@ pcl_ros::FeatureFromNormals::subscribe () // Register callbacks if (approximate_sync_) - sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4)); + sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); else - sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4)); + sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/filters/crop_box.cpp b/pcl_ros/src/pcl_ros/filters/crop_box.cpp index af173dcc4..70ab986b1 100644 --- a/pcl_ros/src/pcl_ros/filters/crop_box.cpp +++ b/pcl_ros/src/pcl_ros/filters/crop_box.cpp @@ -46,7 +46,7 @@ pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service) // Enable the dynamic reconfigure service has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&CropBox::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&CropBox::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); return (true); diff --git a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp index 89b1608ce..73ab4074f 100644 --- a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp +++ b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp @@ -45,7 +45,7 @@ pcl_ros::ExtractIndices::child_init (ros::NodeHandle &nh, bool &has_service) has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); use_indices_ = true; diff --git a/pcl_ros/src/pcl_ros/filters/filter.cpp b/pcl_ros/src/pcl_ros/filters/filter.cpp index 0bfe6d3de..e704912b6 100644 --- a/pcl_ros/src/pcl_ros/filters/filter.cpp +++ b/pcl_ros/src/pcl_ros/filters/filter.cpp @@ -116,18 +116,18 @@ pcl_ros::Filter::subscribe() { sync_input_indices_a_ = boost::make_shared > >(max_queue_size_); sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2)); + sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_indices_e_ = boost::make_shared > >(max_queue_size_); sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, _1, pcl_msgs::PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, boost::placeholders::_1, pcl_msgs::PointIndicesConstPtr ())); } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -164,7 +164,7 @@ pcl_ros::Filter::onInit () if (!has_service) { srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&Filter::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&Filter::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); } diff --git a/pcl_ros/src/pcl_ros/filters/passthrough.cpp b/pcl_ros/src/pcl_ros/filters/passthrough.cpp index f85f536b8..73fd2c96d 100644 --- a/pcl_ros/src/pcl_ros/filters/passthrough.cpp +++ b/pcl_ros/src/pcl_ros/filters/passthrough.cpp @@ -45,7 +45,7 @@ pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service) // Enable the dynamic reconfigure service has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&PassThrough::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&PassThrough::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); return (true); diff --git a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp index 6781d26b6..cdc399802 100644 --- a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp +++ b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp @@ -99,13 +99,13 @@ pcl_ros::ProjectInliers::subscribe () { sync_input_indices_model_a_ = boost::make_shared > > (max_queue_size_); sync_input_indices_model_a_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_); - sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3)); + sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_input_indices_model_e_ = boost::make_shared > > (max_queue_size_); sync_input_indices_model_e_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_); - sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3)); + sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } } diff --git a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp index 4b242db63..aa5c91fac 100644 --- a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp +++ b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp @@ -45,7 +45,7 @@ pcl_ros::RadiusOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_servic // Enable the dynamic reconfigure service has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); return (true); diff --git a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp index fa69a756d..e6e74cd1b 100644 --- a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp +++ b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp @@ -45,7 +45,7 @@ pcl_ros::StatisticalOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_s // Enable the dynamic reconfigure service has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); return (true); diff --git a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp index 476a22152..07687f7f6 100644 --- a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp +++ b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp @@ -45,7 +45,7 @@ pcl_ros::VoxelGrid::child_init (ros::NodeHandle &nh, bool &has_service) // Enable the dynamic reconfigure service has_service = true; srv_ = boost::make_shared > (nh); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); return (true); diff --git a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp index b0425ff03..47d0bb4a5 100644 --- a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp +++ b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp @@ -118,7 +118,7 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe () } // Bogus null filter - filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, _1)); + filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, boost::placeholders::_1)); switch (input_topics_.size ()) { @@ -186,9 +186,9 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe () } if (approximate_sync_) - ts_a_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8)); + ts_a_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8)); else - ts_e_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8)); + ts_e_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8)); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp index 2d41b6821..e9a03621b 100644 --- a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp @@ -76,7 +76,7 @@ pcl_ros::EuclideanClusterExtraction::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&EuclideanClusterExtraction::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&EuclideanClusterExtraction::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n" @@ -108,18 +108,18 @@ pcl_ros::EuclideanClusterExtraction::subscribe () { sync_input_indices_a_ = boost::make_shared > > (max_queue_size_); sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_a_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, _2)); + sync_input_indices_a_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_indices_e_ = boost::make_shared > > (max_queue_size_); sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_e_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, PointIndicesConstPtr ())); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp index af445cfd3..4d31ea801 100644 --- a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp @@ -53,7 +53,7 @@ pcl_ros::ExtractPolygonalPrismData::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); // Advertise the output topics @@ -85,7 +85,7 @@ pcl_ros::ExtractPolygonalPrismData::subscribe () } else { - sub_input_filter_.registerCallback (bind (&ExtractPolygonalPrismData::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&ExtractPolygonalPrismData::input_callback, this, boost::placeholders::_1)); if (approximate_sync_) sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, nf_); @@ -94,9 +94,9 @@ pcl_ros::ExtractPolygonalPrismData::subscribe () } // Register callbacks if (approximate_sync_) - sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3)); + sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); else - sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3)); + sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp index 06b136152..4ca23d651 100644 --- a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp @@ -107,7 +107,7 @@ pcl_ros::SACSegmentation::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared >(*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&SACSegmentation::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&SACSegmentation::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n" @@ -144,15 +144,15 @@ pcl_ros::SACSegmentation::subscribe () if (latched_indices_) { // Subscribe to a callback that saves the indices - sub_indices_filter_.registerCallback (bind (&SACSegmentation::indices_callback, this, _1)); + sub_indices_filter_.registerCallback (bind (&SACSegmentation::indices_callback, this, boost::placeholders::_1)); // Subscribe to a callback that sets the header of the saved indices to the cloud header - sub_input_filter_.registerCallback (bind (&SACSegmentation::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&SACSegmentation::input_callback, this, boost::placeholders::_1)); // Synchronize the two topics. No need for an approximate synchronizer here, as we'll // match the timestamps exactly sync_input_indices_e_ = boost::make_shared > > (max_queue_size_); sync_input_indices_e_->connectInput (sub_input_filter_, nf_pi_); - sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } // "latched_indices" not set, proceed with regular pairs else @@ -161,19 +161,19 @@ pcl_ros::SACSegmentation::subscribe () { sync_input_indices_a_ = boost::make_shared > > (max_queue_size_); sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_a_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2)); + sync_input_indices_a_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_indices_e_ = boost::make_shared > > (max_queue_size_); sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&SACSegmentation::input_indices_callback, this, _1, PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", max_queue_size_, bind (&SACSegmentation::input_indices_callback, this, boost::placeholders::_1, PointIndicesConstPtr ())); } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -367,7 +367,7 @@ pcl_ros::SACSegmentationFromNormals::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&SACSegmentationFromNormals::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&SACSegmentationFromNormals::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); // Advertise the output topics @@ -471,7 +471,7 @@ pcl_ros::SACSegmentationFromNormals::subscribe () else { // Create a different callback for copying over the timestamp to fake indices - sub_input_filter_.registerCallback (bind (&SACSegmentationFromNormals::input_callback, this, _1)); + sub_input_filter_.registerCallback (bind (&SACSegmentationFromNormals::input_callback, this, boost::placeholders::_1)); if (approximate_sync_) sync_input_normals_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_); @@ -480,9 +480,9 @@ pcl_ros::SACSegmentationFromNormals::subscribe () } if (approximate_sync_) - sync_input_normals_indices_a_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, _1, _2, _3)); + sync_input_normals_indices_a_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); else - sync_input_normals_indices_e_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, _1, _2, _3)); + sync_input_normals_indices_e_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp index bde054bb5..1066ea3f0 100644 --- a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp @@ -65,20 +65,20 @@ pcl_ros::SegmentDifferences::subscribe () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&SegmentDifferences::config_callback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&SegmentDifferences::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); if (approximate_sync_) { sync_input_target_a_ = boost::make_shared > > (max_queue_size_); sync_input_target_a_->connectInput (sub_input_filter_, sub_target_filter_); - sync_input_target_a_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, _1, _2)); + sync_input_target_a_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_target_e_ = boost::make_shared > > (max_queue_size_); sync_input_target_e_->connectInput (sub_input_filter_, sub_target_filter_); - sync_input_target_e_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, _1, _2)); + sync_input_target_e_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp index 6719aceeb..08f52f424 100644 --- a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp +++ b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp @@ -76,19 +76,19 @@ pcl_ros::ConvexHull2D::subscribe() sync_input_indices_a_ = boost::make_shared > >(max_queue_size_); // surface not enabled, connect the input-indices duo and register sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_a_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, _1, _2)); + sync_input_indices_a_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_indices_e_ = boost::make_shared > >(max_queue_size_); // surface not enabled, connect the input-indices duo and register sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_e_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&ConvexHull2D::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", 1, bind (&ConvexHull2D::input_indices_callback, this, _1, PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", 1, bind (&ConvexHull2D::input_indices_callback, this, boost::placeholders::_1, PointIndicesConstPtr ())); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp index 46c6a39dd..8baa9cb67 100644 --- a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp +++ b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp @@ -62,7 +62,7 @@ pcl_ros::MovingLeastSquares::onInit () // Enable the dynamic reconfigure service srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind (&MovingLeastSquares::config_callback, this, _1, _2 ); + dynamic_reconfigure::Server::CallbackType f = boost::bind (&MovingLeastSquares::config_callback, this, boost::placeholders::_1, boost::placeholders::_2 ); srv_->setCallback (f); // ---[ Optional parameters @@ -93,19 +93,19 @@ pcl_ros::MovingLeastSquares::subscribe () sync_input_indices_a_ = boost::make_shared > >(max_queue_size_); // surface not enabled, connect the input-indices duo and register sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_a_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, _1, _2)); + sync_input_indices_a_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_input_indices_e_ = boost::make_shared > >(max_queue_size_); // surface not enabled, connect the input-indices duo and register sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_); - sync_input_indices_e_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, _1, _2)); + sync_input_indices_e_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2)); } } else // Subscribe in an old fashion to input only (no filters) - sub_input_ = pnh_->subscribe ("input", 1, bind (&MovingLeastSquares::input_indices_callback, this, _1, PointIndicesConstPtr ())); + sub_input_ = pnh_->subscribe ("input", 1, bind (&MovingLeastSquares::input_indices_callback, this, boost::placeholders::_1, PointIndicesConstPtr ())); } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/test/test_tf_message_filter_pcl.cpp b/pcl_ros/src/test/test_tf_message_filter_pcl.cpp index 073e358c8..b324fc8a4 100644 --- a/pcl_ros/src/test/test_tf_message_filter_pcl.cpp +++ b/pcl_ros/src/test/test_tf_message_filter_pcl.cpp @@ -37,7 +37,7 @@ #include #include -#include +#include #include #include @@ -104,7 +104,7 @@ TEST(MessageFilter, noTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); boost::shared_ptr msg(new PCDType); ros::Time stamp = ros::Time::now(); @@ -120,7 +120,7 @@ TEST(MessageFilter, noTransformsSameFrame) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); boost::shared_ptr msg(new PCDType); ros::Time stamp = ros::Time::now(); @@ -136,7 +136,7 @@ TEST(MessageFilter, preexistingTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); boost::shared_ptr msg(new PCDType); @@ -157,7 +157,7 @@ TEST(MessageFilter, postTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); ros::Time stamp = ros::Time::now(); boost::shared_ptr msg(new PCDType); @@ -182,8 +182,8 @@ TEST(MessageFilter, queueSize) tf::TransformListener tf_client; Notification n(10); MessageFilter filter(tf_client, "frame1", 10); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); ros::Time stamp = ros::Time::now(); std::uint64_t pcl_stamp; @@ -215,7 +215,7 @@ TEST(MessageFilter, setTargetFrame) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); filter.setTargetFrame("frame1000"); ros::Time stamp = ros::Time::now(); @@ -237,7 +237,7 @@ TEST(MessageFilter, multipleTargetFrames) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); std::vector target_frames; target_frames.push_back("frame1"); @@ -276,7 +276,7 @@ TEST(MessageFilter, tolerance) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); filter.setTolerance(offset); ros::Time stamp = ros::Time::now(); @@ -316,7 +316,7 @@ TEST(MessageFilter, outTheBackFailure) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); ros::Time stamp = ros::Time::now(); boost::shared_ptr msg(new PCDType); @@ -339,7 +339,7 @@ TEST(MessageFilter, emptyFrameIDFailure) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); boost::shared_ptr msg(new PCDType); msg->header.frame_id = ""; From bc073a6525f17eaf313efb456b4034d827b46d09 Mon Sep 17 00:00:00 2001 From: Jochen Sprickerhof Date: Tue, 1 Feb 2022 22:04:21 +0100 Subject: [PATCH 2/3] Drop old C++ standard --- pcl_ros/CMakeLists.txt | 9 --------- 1 file changed, 9 deletions(-) diff --git a/pcl_ros/CMakeLists.txt b/pcl_ros/CMakeLists.txt index 2466227dd..6230e32ef 100644 --- a/pcl_ros/CMakeLists.txt +++ b/pcl_ros/CMakeLists.txt @@ -1,15 +1,6 @@ cmake_minimum_required(VERSION 3.0.2) project(pcl_ros) -# CMake 3.1 added support for CMAKE_CXX_STANDARD to manage the C++ standard version -# Use CMake C++ standard management where possible for better interoperability -# with dependencies that export target standards and/or features -if (${CMAKE_VERSION} VERSION_LESS "3.1") - add_compile_options(-std=c++14) -else() - set(CMAKE_CXX_STANDARD 14) -endif() - ## Find catkin packages find_package(catkin REQUIRED COMPONENTS dynamic_reconfigure From aca6fa1bb7fb8187b302930864470f8799b67d9f Mon Sep 17 00:00:00 2001 From: v4hn Date: Sat, 29 Oct 2022 18:10:51 +0200 Subject: [PATCH 3/3] update deprecated traits include as reported by PCL 1.12. --- pcl_ros/include/pcl_ros/point_cloud.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pcl_ros/include/pcl_ros/point_cloud.h b/pcl_ros/include/pcl_ros/point_cloud.h index 1bb6ab9eb..26e36c1be 100644 --- a/pcl_ros/include/pcl_ros/point_cloud.h +++ b/pcl_ros/include/pcl_ros/point_cloud.h @@ -3,7 +3,7 @@ #include #include -#include +#include #include #include #include