@@ -120,7 +120,7 @@ namespace jsk_pcl_ros
120
120
// dynamic_reconfigure
121
121
srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
122
122
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);
124
124
srv_->setCallback (f);
125
125
126
126
negative_indices_pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, " negative_indices" , 1 );
@@ -153,24 +153,24 @@ namespace jsk_pcl_ros
153
153
if (use_async_) {
154
154
async_align_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncAlignPolicy> >(queue_size_);
155
155
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));
157
157
}
158
158
else {
159
159
sync_align_ = boost::make_shared<message_filters::Synchronizer<SyncAlignPolicy> >(queue_size_);
160
160
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));
162
162
}
163
163
}
164
164
else {
165
165
if (use_async_) {
166
166
async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
167
167
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));
169
169
}
170
170
else {
171
171
sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
172
172
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));
174
174
}
175
175
}
176
176
}
0 commit comments