Skip to content

Commit fde5ccb

Browse files
Jochen Sprickerhofv4hn
authored andcommitted
Switch to new boost/bind/bind.hpp
1 parent eb8f009 commit fde5ccb

17 files changed

+68
-68
lines changed

pcl_ros/src/pcl_ros/features/feature.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ pcl_ros::Feature::onInit ()
8080

8181
// Enable the dynamic reconfigure service
8282
srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
83-
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&Feature::config_callback, this, _1, _2);
83+
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&Feature::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
8484
srv_->setCallback (f);
8585

8686
NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
@@ -124,7 +124,7 @@ pcl_ros::Feature::subscribe ()
124124
}
125125
else // Use only indices
126126
{
127-
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1));
127+
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1));
128128
// surface not enabled, connect the input-indices duo and register
129129
if (approximate_sync_)
130130
sync_input_surface_indices_a_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
@@ -134,7 +134,7 @@ pcl_ros::Feature::subscribe ()
134134
}
135135
else // Use only surface
136136
{
137-
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1));
137+
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1));
138138
// indices not enabled, connect the input-surface duo and register
139139
sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
140140
if (approximate_sync_)
@@ -144,13 +144,13 @@ pcl_ros::Feature::subscribe ()
144144
}
145145
// Register callbacks
146146
if (approximate_sync_)
147-
sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
147+
sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
148148
else
149-
sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
149+
sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
150150
}
151151
else
152152
// Subscribe in an old fashion to input only (no filters)
153-
sub_input_ = pnh_->subscribe<PointCloudIn> ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, _1, PointCloudInConstPtr (), PointIndicesConstPtr ()));
153+
sub_input_ = pnh_->subscribe<PointCloudIn> ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, PointCloudInConstPtr (), PointIndicesConstPtr ()));
154154
}
155155

156156
////////////////////////////////////////////////////////////////////////////////////////////
@@ -300,7 +300,7 @@ pcl_ros::FeatureFromNormals::onInit ()
300300

301301
// Enable the dynamic reconfigure service
302302
srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
303-
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, _1, _2);
303+
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
304304
srv_->setCallback (f);
305305

306306
NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
@@ -345,7 +345,7 @@ pcl_ros::FeatureFromNormals::subscribe ()
345345
}
346346
else // Use only indices
347347
{
348-
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
348+
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));
349349
if (approximate_sync_)
350350
// surface not enabled, connect the input-indices duo and register
351351
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 ()
359359
// indices not enabled, connect the input-surface duo and register
360360
sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
361361

362-
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
362+
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));
363363
if (approximate_sync_)
364364
sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
365365
else
@@ -368,7 +368,7 @@ pcl_ros::FeatureFromNormals::subscribe ()
368368
}
369369
else
370370
{
371-
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
371+
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));
372372

373373
if (approximate_sync_)
374374
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 ()
378378

379379
// Register callbacks
380380
if (approximate_sync_)
381-
sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
381+
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));
382382
else
383-
sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
383+
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));
384384
}
385385

386386
//////////////////////////////////////////////////////////////////////////////////////////////

pcl_ros/src/pcl_ros/filters/crop_box.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
4646
// Enable the dynamic reconfigure service
4747
has_service = true;
4848
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > (nh);
49-
dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, _1, _2);
49+
dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
5050
srv_->setCallback (f);
5151

5252
return (true);

pcl_ros/src/pcl_ros/filters/extract_indices.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ pcl_ros::ExtractIndices::child_init (ros::NodeHandle &nh, bool &has_service)
4545
has_service = true;
4646

4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig> > (nh);
48-
dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig>::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, _1, _2);
48+
dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig>::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
4949
srv_->setCallback (f);
5050

5151
use_indices_ = true;

pcl_ros/src/pcl_ros/filters/filter.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -116,18 +116,18 @@ pcl_ros::Filter::subscribe()
116116
{
117117
sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
118118
sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
119-
sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
119+
sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
120120
}
121121
else
122122
{
123123
sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
124124
sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
125-
sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
125+
sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
126126
}
127127
}
128128
else
129129
// Subscribe in an old fashion to input only (no filters)
130-
sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, _1, pcl_msgs::PointIndicesConstPtr ()));
130+
sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, boost::placeholders::_1, pcl_msgs::PointIndicesConstPtr ()));
131131
}
132132

133133
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -164,7 +164,7 @@ pcl_ros::Filter::onInit ()
164164
if (!has_service)
165165
{
166166
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (*pnh_);
167-
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&Filter::config_callback, this, _1, _2);
167+
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&Filter::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
168168
srv_->setCallback (f);
169169
}
170170

pcl_ros/src/pcl_ros/filters/passthrough.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service)
4545
// Enable the dynamic reconfigure service
4646
has_service = true;
4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (nh);
48-
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, _1, _2);
48+
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
4949
srv_->setCallback (f);
5050

5151
return (true);

pcl_ros/src/pcl_ros/filters/project_inliers.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -99,13 +99,13 @@ pcl_ros::ProjectInliers::subscribe ()
9999
{
100100
sync_input_indices_model_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
101101
sync_input_indices_model_a_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
102-
sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
102+
sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
103103
}
104104
else
105105
{
106106
sync_input_indices_model_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
107107
sync_input_indices_model_e_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
108-
sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
108+
sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
109109
}
110110
}
111111

pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ pcl_ros::RadiusOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_servic
4545
// Enable the dynamic reconfigure service
4646
has_service = true;
4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig> > (nh);
48-
dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig>::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, _1, _2);
48+
dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig>::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
4949
srv_->setCallback (f);
5050

5151
return (true);

pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ pcl_ros::StatisticalOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_s
4545
// Enable the dynamic reconfigure service
4646
has_service = true;
4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig> > (nh);
48-
dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig>::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, _1, _2);
48+
dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig>::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
4949
srv_->setCallback (f);
5050

5151
return (true);

pcl_ros/src/pcl_ros/filters/voxel_grid.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ pcl_ros::VoxelGrid::child_init (ros::NodeHandle &nh, bool &has_service)
4545
// Enable the dynamic reconfigure service
4646
has_service = true;
4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig> > (nh);
48-
dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig>::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, _1, _2);
48+
dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig>::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
4949
srv_->setCallback (f);
5050

5151
return (true);

pcl_ros/src/pcl_ros/io/concatenate_data.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe ()
118118
}
119119

120120
// Bogus null filter
121-
filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, _1));
121+
filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, boost::placeholders::_1));
122122

123123
switch (input_topics_.size ())
124124
{
@@ -186,9 +186,9 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe ()
186186
}
187187

188188
if (approximate_sync_)
189-
ts_a_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8));
189+
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));
190190
else
191-
ts_e_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8));
191+
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));
192192
}
193193

194194
//////////////////////////////////////////////////////////////////////////////////////////////

0 commit comments

Comments
 (0)