@@ -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// ////////////////////////////////////////////////////////////////////////////////////////////
0 commit comments