Skip to content

Commit bc4aa06

Browse files
committed
using boost::placeholders for _1, _2, etc.
1 parent c723e46 commit bc4aa06

File tree

171 files changed

+333
-333
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

171 files changed

+333
-333
lines changed

checkerboard_detector/src/checkerboard_detector.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -136,7 +136,7 @@ class CheckerboardDetector
136136

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

142142
while(1) {

checkerboard_detector/src/objectdetection_transform_echo.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ int main(int argc, char** argv)
142142
message_filters::Synchronizer<SyncPolicy> sync(
143143
SyncPolicy(1000),
144144
detection1_sub, detection2_sub);
145-
sync.registerCallback(boost::bind(&callback, _1, _2));
145+
sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2));
146146
ros::spin();
147147
return 0;
148148
}

cr_capture/src/cr_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ class CRCaptureNode {
7373
CRCaptureNode () : nh_("~"), it_(nh_), sync_(5)
7474
{
7575
// Set up dynamic reconfiguration
76-
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, _1, _2);
76+
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2);
7777
reconfigure_server_.setCallback(f);
7878

7979
// parameter
@@ -171,7 +171,7 @@ class CRCaptureNode {
171171
info_sub_.subscribe(nh_, range_ns_ + "/camera_info", 1);
172172

173173
sync_.connectInput(image_conf_sub_, image_intent_sub_, image_depth_sub_, info_sub_);
174-
sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, _1, _2, _3, _4));
174+
sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
175175
} else {
176176
// not all subscribe
177177
camera_sub_depth_ = it_.subscribeCamera(range_ns_ + "/image", 1, &CRCaptureNode::camerarangeCB, this);

cr_capture/src/cr_node_sync.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ class CRCaptureSyncNode {
7676
CRCaptureSyncNode () : nh_("~"), it_(nh_), sync_(30)
7777
{
7878
// Set up dynamic reconfiguration
79-
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, _1, _2);
79+
ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2);
8080
reconfigure_server_.setCallback(f);
8181

8282
// parameter
@@ -175,7 +175,7 @@ class CRCaptureSyncNode {
175175
sync_.connectInput(image_sub_left_, info_sub_left_, image_sub_right_, info_sub_right_,
176176
image_sub_confi_, image_sub_intent_, image_sub_depth_, info_sub_range_);
177177

178-
sync_.registerCallback(boost::bind(&CRCaptureSyncNode::imageCB, this, _1, _2, _3, _4, _5, _6, _7, _8));
178+
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));
179179

180180
// pull raw data service
181181
nh_.param("pull_raw_data", pull_raw_data, false);

imagesift/src/imagesift.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -92,7 +92,7 @@ namespace imagesift
9292
_subMask.subscribe(*nh_, "mask", 1);
9393
_sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
9494
_sync->connectInput(_subImageWithMask, _subMask);
95-
_sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2));
95+
_sync->registerCallback(boost::bind(&SiftNode::imageCb, this, boost::placeholders::_1, boost::placeholders::_2));
9696
}
9797
_subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this);
9898
}

jsk_libfreenect2/src/driver_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ namespace jsk_libfreenect2
3737
glfwInit();
3838
timer_ = getNodeHandle().createTimer(
3939
ros::Duration(5.0),
40-
boost::bind(&Driver::run, this, _1), true);
40+
boost::bind(&Driver::run, this, boost::placeholders::_1), true);
4141
}
4242

4343
void Driver::run(const ros::TimerEvent&) {

jsk_pcl_ros/src/add_color_from_image_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ namespace jsk_pcl_ros
7070
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
7171
sync_->connectInput(sub_cloud_, sub_image_, sub_info_);
7272
sync_->registerCallback(boost::bind(&AddColorFromImage::addColor,
73-
this, _1, _2, _3));
73+
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
7474
}
7575

7676
void AddColorFromImage::unsubscribe()

jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ namespace jsk_pcl_ros
6767
sub_image_.subscribe(*pnh_, "input/image", 1);
6868
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
6969
sync_->connectInput(sub_cloud_, sub_image_);
70-
sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, _1, _2));
70+
sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, boost::placeholders::_1, boost::placeholders::_2));
7171
}
7272

7373
void AddColorFromImageToOrganized::unsubscribe()

jsk_pcl_ros/src/bilateral_filter_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,7 @@ namespace jsk_pcl_ros
4848
ConnectionBasedNodelet::onInit();
4949
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
5050
typename dynamic_reconfigure::Server<Config>::CallbackType f =
51-
boost::bind (&BilateralFilter::configCallback, this, _1, _2);
51+
boost::bind (&BilateralFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5252
srv_->setCallback (f);
5353

5454
pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);

jsk_pcl_ros/src/border_estimator_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ namespace jsk_pcl_ros
5050
pnh_->param("model_type", model_type_, std::string("planar"));
5151
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
5252
typename dynamic_reconfigure::Server<Config>::CallbackType f =
53-
boost::bind (&BorderEstimator::configCallback, this, _1, _2);
53+
boost::bind (&BorderEstimator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5454
srv_->setCallback (f);
5555

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

jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,7 @@ namespace jsk_pcl_ros
4747
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
4848
dynamic_reconfigure::Server<Config>::CallbackType f =
4949
boost::bind (
50-
&BoundingBoxFilter::configCallback, this, _1, _2);
50+
&BoundingBoxFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5151
srv_->setCallback (f);
5252

5353
////////////////////////////////////////////////////////
@@ -82,9 +82,9 @@ namespace jsk_pcl_ros
8282
sub_indices_.subscribe(*pnh_, "input_indices", 1);
8383
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
8484
sync_->connectInput(sub_box_, sub_indices_);
85-
sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, _1, _2));
85+
sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, boost::placeholders::_1, boost::placeholders::_2));
8686
} else {
87-
sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1));
87+
sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, boost::placeholders::_1));
8888
}
8989
}
9090

jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -117,11 +117,11 @@ namespace jsk_pcl_ros
117117
sub_disparity_);
118118
sync_->registerCallback(boost::bind(&CaptureStereoSynchronizer::republish,
119119
this,
120-
_1,
121-
_2,
122-
_3,
123-
_4,
124-
_5,
120+
boost::placeholders::_1,
121+
boost::placeholders::_2,
122+
boost::placeholders::_3,
123+
boost::placeholders::_4,
124+
boost::placeholders::_5,
125125
_6,
126126
_7));
127127
}

jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,7 @@ namespace jsk_pcl_ros
120120
// dynamic_reconfigure
121121
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
122122
dynamic_reconfigure::Server<Config>::CallbackType f =
123-
boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, _1, _2);
123+
boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
124124
srv_->setCallback(f);
125125

126126
negative_indices_pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "negative_indices", 1);
@@ -153,24 +153,24 @@ namespace jsk_pcl_ros
153153
if (use_async_) {
154154
async_align_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncAlignPolicy> >(queue_size_);
155155
async_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_);
156-
async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
156+
async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
157157
}
158158
else {
159159
sync_align_ = boost::make_shared<message_filters::Synchronizer<SyncAlignPolicy> >(queue_size_);
160160
sync_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_);
161-
sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
161+
sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
162162
}
163163
}
164164
else {
165165
if (use_async_) {
166166
async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
167167
async_->connectInput(sub_input_, sub_target_);
168-
async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
168+
async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2));
169169
}
170170
else {
171171
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
172172
sync_->connectInput(sub_input_, sub_target_);
173-
sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
173+
sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2));
174174
}
175175
}
176176
}

jsk_pcl_ros/src/color_based_region_growing_segmentation_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ namespace jsk_pcl_ros
4949
ConnectionBasedNodelet::onInit();
5050
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
5151
dynamic_reconfigure::Server<Config>::CallbackType f=
52-
boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, _1, _2);
52+
boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5353
srv_->setCallback (f);
5454
pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
5555
onInitPostProcess();

jsk_pcl_ros/src/color_filter_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -342,7 +342,7 @@ namespace jsk_pcl_ros
342342

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

348348
onInitPostProcess();
@@ -356,7 +356,7 @@ namespace jsk_pcl_ros
356356
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(10);
357357
sub_indices_.subscribe(*pnh_, "indices", 1);
358358
sync_->connectInput(sub_input_, sub_indices_);
359-
sync_->registerCallback(boost::bind(&ColorFilter::filter, this, _1, _2));
359+
sync_->registerCallback(boost::bind(&ColorFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2));
360360
//sub_input_ = pnh_->subscribe("input", 1, &RGBColorFilter::filter, this);
361361
}
362362
else {

jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ namespace jsk_pcl_ros
5252

5353
srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
5454
dynamic_reconfigure::Server<Config>::CallbackType f =
55-
boost::bind(&ColorHistogramClassifier::configCallback, this, _1, _2);
55+
boost::bind(&ColorHistogramClassifier::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5656
srv_->setCallback(f);
5757
pub_class_ = advertise<jsk_recognition_msgs::ClassificationResult>(*pnh_, "output", 1);
5858
onInitPostProcess();

jsk_pcl_ros/src/color_histogram_filter_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ namespace jsk_pcl_ros
5353

5454
srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
5555
dynamic_reconfigure::Server<Config>::CallbackType f =
56-
boost::bind(&ColorHistogramFilter::configCallback, this, _1, _2);
56+
boost::bind(&ColorHistogramFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5757
srv_->setCallback(f);
5858
pub_histogram_ = advertise<jsk_recognition_msgs::ColorHistogramArray>(*pnh_, "output", 1);
5959
pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/indices", 1);
@@ -94,7 +94,7 @@ namespace jsk_pcl_ros
9494
sub_indices_.subscribe(*pnh_, "input/indices", 1);
9595
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
9696
sync_->connectInput(sub_histogram_, sub_indices_);
97-
sync_->registerCallback(boost::bind(&ColorHistogramFilter::feature, this, _1, _2));
97+
sync_->registerCallback(boost::bind(&ColorHistogramFilter::feature, this, boost::placeholders::_1, boost::placeholders::_2));
9898
}
9999

100100
void ColorHistogramFilter::unsubscribe()

jsk_pcl_ros/src/color_histogram_matcher_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ namespace jsk_pcl_ros
5353
ConnectionBasedNodelet::onInit();
5454
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
5555
dynamic_reconfigure::Server<Config>::CallbackType f =
56-
boost::bind (&ColorHistogramMatcher::configCallback, this, _1, _2);
56+
boost::bind (&ColorHistogramMatcher::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5757
srv_->setCallback (f);
5858

5959
policy_ = USE_HUE_AND_SATURATION;
@@ -98,7 +98,7 @@ namespace jsk_pcl_ros
9898
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
9999
sync_->connectInput(sub_input_, sub_indices_);
100100
sync_->registerCallback(boost::bind(&ColorHistogramMatcher::feature,
101-
this, _1, _2));
101+
this, boost::placeholders::_1, boost::placeholders::_2));
102102
}
103103

104104
void ColorHistogramMatcher::unsubscribe()

jsk_pcl_ros/src/color_histogram_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ namespace jsk_pcl_ros
5454
DiagnosticNodelet::onInit();
5555
srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
5656
dynamic_reconfigure::Server<Config>::CallbackType f =
57-
boost::bind(&ColorHistogram::configCallback, this, _1, _2);
57+
boost::bind(&ColorHistogram::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
5858
srv_->setCallback(f);
5959
pub_histogram_ = advertise<jsk_recognition_msgs::ColorHistogramArray>(*pnh_, "output", 1);
6060
onInitPostProcess();
@@ -94,7 +94,7 @@ namespace jsk_pcl_ros
9494
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
9595
sync_->connectInput(sub_cloud_, sub_indices_);
9696
sync_->registerCallback(boost::bind(&ColorHistogram::feature,
97-
this, _1, _2));
97+
this, boost::placeholders::_1, boost::placeholders::_2));
9898
}
9999

100100
void ColorHistogram::unsubscribe()

jsk_pcl_ros/src/container_occupancy_detector_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,11 @@ namespace jsk_pcl_ros{
7373
if(approximate_sync_){
7474
ap_sync_ = std::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
7575
ap_sync_ -> connectInput(sub_boxes_, sub_points_, sub_point_indices_);
76-
ap_sync_ -> registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, _1, _2, _3));
76+
ap_sync_ -> registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
7777
}else{
7878
sync_ = std::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
7979
sync_->connectInput(sub_boxes_, sub_points_, sub_point_indices_);
80-
sync_->registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, _1, _2, _3));
80+
sync_->registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
8181
}
8282
}
8383

jsk_pcl_ros/src/depth_calibration_nodelet.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ namespace jsk_pcl_ros
122122
sub_camera_info_.subscribe(*pnh_, "camera_info", 1);
123123
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
124124
sync_->connectInput(sub_input_, sub_camera_info_);
125-
sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, _1, _2));
125+
sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, boost::placeholders::_1, boost::placeholders::_2));
126126
}
127127

128128
void DepthCalibration::unsubscribe()

jsk_pcl_ros/src/depth_image_creator_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -132,11 +132,11 @@ void jsk_pcl_ros::DepthImageCreator::subscribe() {
132132
if (use_approximate) {
133133
sync_inputs_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > (max_queue_size_);
134134
sync_inputs_a_->connectInput (sub_info_, sub_cloud_);
135-
sync_inputs_a_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2));
135+
sync_inputs_a_->registerCallback (bind (&DepthImageCreator::callback_sync, this, boost::placeholders::_1, boost::placeholders::_2));
136136
} else {
137137
sync_inputs_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > (max_queue_size_);
138138
sync_inputs_e_->connectInput (sub_info_, sub_cloud_);
139-
sync_inputs_e_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2));
139+
sync_inputs_e_->registerCallback (bind (&DepthImageCreator::callback_sync, this, boost::placeholders::_1, boost::placeholders::_2));
140140
}
141141
}
142142
} else {

jsk_pcl_ros/src/edge_depth_refinement_nodelet.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ namespace jsk_pcl_ros
6767
////////////////////////////////////////////////////////
6868
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
6969
dynamic_reconfigure::Server<Config>::CallbackType f =
70-
boost::bind (&EdgeDepthRefinement::configCallback, this, _1, _2);
70+
boost::bind (&EdgeDepthRefinement::configCallback, this, boost::placeholders::_1, boost::placeholders::_2);
7171
srv_->setCallback (f);
7272

7373
onInitPostProcess();
@@ -94,7 +94,7 @@ namespace jsk_pcl_ros
9494
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
9595
sync_->connectInput(sub_input_, sub_indices_);
9696
sync_->registerCallback(boost::bind(&EdgeDepthRefinement::refine,
97-
this, _1, _2));
97+
this, boost::placeholders::_1, boost::placeholders::_2));
9898
}
9999

100100
void EdgeDepthRefinement::unsubscribe()

0 commit comments

Comments
 (0)