From 73f7a31b85eeff68b4c90771cb5804c6e332478b Mon Sep 17 00:00:00 2001 From: Lucas Walter Date: Mon, 29 Apr 2024 16:33:58 -0700 Subject: [PATCH] using boost::placeholders for _1, _2, etc. --- .../src/checkerboard_detector.cpp | 2 +- .../src/objectdetection_transform_echo.cpp | 2 +- cr_capture/src/cr_node.cpp | 4 +-- cr_capture/src/cr_node_sync.cpp | 4 +-- imagesift/src/imagesift.cpp | 2 +- jsk_libfreenect2/src/driver_nodelet.cpp | 2 +- .../src/add_color_from_image_nodelet.cpp | 2 +- ..._color_from_image_to_organized_nodelet.cpp | 2 +- jsk_pcl_ros/src/bilateral_filter_nodelet.cpp | 2 +- jsk_pcl_ros/src/border_estimator_nodelet.cpp | 4 +-- .../src/bounding_box_filter_nodelet.cpp | 6 ++-- .../capture_stereo_synchronizer_nodelet.cpp | 10 +++---- ...uster_point_indices_decomposer_nodelet.cpp | 10 +++---- ...ed_region_growing_segmentation_nodelet.cpp | 2 +- jsk_pcl_ros/src/color_filter_nodelet.cpp | 4 +-- .../color_histogram_classifier_nodelet.cpp | 2 +- .../src/color_histogram_filter_nodelet.cpp | 4 +-- .../src/color_histogram_matcher_nodelet.cpp | 4 +-- jsk_pcl_ros/src/color_histogram_nodelet.cpp | 4 +-- .../container_occupancy_detector_nodelet.cpp | 4 +-- jsk_pcl_ros/src/depth_calibration_nodelet.cpp | 2 +- .../src/depth_image_creator_nodelet.cpp | 4 +-- .../src/edge_depth_refinement_nodelet.cpp | 4 +-- .../src/edgebased_cube_finder_nodelet.cpp | 4 +-- .../environment_plane_modeling_nodelet.cpp | 4 +-- .../euclidean_cluster_extraction_nodelet.cpp | 6 ++-- ...extract_cuboid_particles_top_n_nodelet.cpp | 2 +- jsk_pcl_ros/src/extract_indices_nodelet.cpp | 4 +-- .../src/feature_registration_nodelet.cpp | 6 ++-- .../src/find_object_on_plane_nodelet.cpp | 2 +- .../src/fisheye_sphere_publisher_nodelet.cpp | 2 +- jsk_pcl_ros/src/fuse_images.cpp | 6 ++-- ...geometric_consistency_grouping_nodelet.cpp | 6 ++-- jsk_pcl_ros/src/grid_sampler_nodelet.cpp | 2 +- jsk_pcl_ros/src/handle_estimator_nodelet.cpp | 4 +-- .../src/heightmap_converter_nodelet.cpp | 2 +- ...ghtmap_morphological_filtering_nodelet.cpp | 2 +- .../heightmap_time_accumulation_nodelet.cpp | 4 +-- .../src/hinted_handle_estimator_nodelet.cpp | 2 +- .../src/hinted_plane_detector_nodelet.cpp | 4 +-- .../src/hinted_stick_finder_nodelet.cpp | 4 +-- jsk_pcl_ros/src/icp_registration_nodelet.cpp | 8 ++--- jsk_pcl_ros/src/image_rotate_nodelet.cpp | 6 ++-- ...incremental_model_registration_nodelet.cpp | 2 +- .../interactive_cuboid_likelihood_nodelet.cpp | 8 ++--- jsk_pcl_ros/src/kinfu_nodelet.cpp | 6 ++-- .../src/line_segment_collector_nodelet.cpp | 4 +-- .../src/line_segment_detector_nodelet.cpp | 6 ++-- jsk_pcl_ros/src/linemod_nodelet.cpp | 4 +-- .../src/mask_image_cluster_filter_nodelet.cpp | 2 +- .../moving_least_square_smoothing_nodelet.cpp | 2 +- .../src/multi_plane_extraction_nodelet.cpp | 10 +++---- .../multi_plane_sac_segmentation_nodelet.cpp | 10 +++---- .../src/normal_direction_filter_nodelet.cpp | 4 +-- ...rmal_estimation_integral_image_nodelet.cpp | 2 +- .../src/normal_estimation_omp_nodelet.cpp | 2 +- .../src/octomap_server_contact_nodelet.cpp | 4 +-- .../src/octree_change_publisher_nodelet.cpp | 2 +- jsk_pcl_ros/src/octree_voxel_grid_nodelet.cpp | 2 +- .../src/organized_edge_detector_nodelet.cpp | 2 +- ...nized_multi_plane_segmentation_nodelet.cpp | 8 ++--- .../src/organized_pass_through_nodelet.cpp | 2 +- ...ed_statistical_outlier_removal_nodelet.cpp | 2 +- .../src/parallel_edge_finder_nodelet.cpp | 4 +-- .../src/particle_filter_tracking_nodelet.cpp | 6 ++-- jsk_pcl_ros/src/people_detection_nodelet.cpp | 2 +- ...ane_supported_cuboid_estimator_nodelet.cpp | 12 ++++---- .../pointcloud_database_server_nodelet.cpp | 4 +-- .../src/pointcloud_localization_nodelet.cpp | 4 +-- jsk_pcl_ros/src/pointcloud_moveit_filter.cpp | 10 +++---- .../src/pointcloud_screenpoint_nodelet.cpp | 30 +++++++++---------- jsk_pcl_ros/src/ppf_registration_nodelet.cpp | 10 +++---- .../primitive_shape_classifier_nodelet.cpp | 4 +-- .../src/rearrange_bounding_box_nodelet.cpp | 2 +- ...ng_multiple_plane_segmentation_nodelet.cpp | 4 +-- .../region_growing_segmentation_nodelet.cpp | 2 +- .../src/resize_points_publisher_nodelet.cpp | 6 ++-- jsk_pcl_ros/src/roi_clipper_nodelet.cpp | 2 +- .../selected_cluster_publisher_nodelet.cpp | 2 +- jsk_pcl_ros/src/snapit_nodelet.cpp | 2 +- .../src/supervoxel_segmentation_nodelet.cpp | 2 +- .../src/target_adaptive_tracking_nodelet.cpp | 6 ++-- jsk_pcl_ros/src/torus_finder_nodelet.cpp | 2 +- jsk_pcl_ros/src/uniform_sampling_nodelet.cpp | 2 +- .../src/voxel_grid_large_scale_nodelet.cpp | 2 +- .../src/add_point_indices_nodelet.cpp | 4 +-- ...ding_box_array_to_bounding_box_nodelet.cpp | 2 +- .../src/cloud_on_plane_nodelet.cpp | 6 ++-- ...ter_point_indices_label_filter_nodelet.cpp | 6 ++-- ...point_indices_to_point_indices_nodelet.cpp | 2 +- .../colorize_distance_from_plane_nodelet.cpp | 4 +-- .../src/delay_pointcloud_nodelet.cpp | 4 +-- .../src/depth_image_error_nodelet.cpp | 4 +-- ...to_depth_considered_mask_image_nodelet.cpp | 6 ++-- .../src/normal_concatenater_nodelet.cpp | 4 +-- .../planar_pointcloud_simulator_nodelet.cpp | 2 +- .../src/plane_concatenator_nodelet.cpp | 4 +-- .../src/plane_reasoner_nodelet.cpp | 4 +-- .../src/plane_rejector_nodelet.cpp | 10 +++---- .../point_indices_to_mask_image_nodelet.cpp | 4 +-- ...oud_relative_from_pose_stamped_nodelet.cpp | 4 +-- .../src/pointcloud_to_mask_image_nodelet.cpp | 2 +- .../src/pointcloud_to_pcd_nodelet.cpp | 4 +-- .../src/polygon_appender_nodelet.cpp | 2 +- ...polygon_array_angle_likelihood_nodelet.cpp | 2 +- .../polygon_array_area_likelihood_nodelet.cpp | 2 +- ...ygon_array_distance_likelihood_nodelet.cpp | 2 +- ...on_array_foot_angle_likelihood_nodelet.cpp | 2 +- ...olygon_array_likelihood_filter_nodelet.cpp | 4 +-- .../src/polygon_array_transformer_nodelet.cpp | 2 +- .../src/polygon_array_unwrapper_nodelet.cpp | 4 +-- .../src/polygon_array_wrapper_nodelet.cpp | 2 +- .../src/polygon_flipper_nodelet.cpp | 4 +-- .../src/polygon_magnifier_nodelet.cpp | 2 +- .../src/polygon_points_sampler_nodelet.cpp | 4 +-- ...stamped_to_gaussian_pointcloud_nodelet.cpp | 2 +- ...spherical_pointcloud_simulator_nodelet.cpp | 4 +-- ...static_polygon_array_publisher_nodelet.cpp | 2 +- .../src/subtract_point_indices_nodelet.cpp | 4 +-- ...f_transform_bounding_box_array_nodelet.cpp | 2 +- .../src/tf_transform_bounding_box_nodelet.cpp | 2 +- .../src/tf_transform_cloud_nodelet.cpp | 2 +- ...orm_pointcloud_in_bounding_box_nodelet.cpp | 2 +- jsk_perception/src/add_mask_image.cpp | 4 +-- jsk_perception/src/apply_mask_image.cpp | 4 +-- .../src/background_substraction_nodelet.cpp | 2 +- jsk_perception/src/blob_detector.cpp | 2 +- jsk_perception/src/bounding_box_to_rect.cpp | 10 +++---- jsk_perception/src/camshiftdemo.cpp | 2 +- jsk_perception/src/color_histogram.cpp | 6 ++-- .../src/color_histogram_label_match.cpp | 6 ++-- .../src/color_histogram_sliding_matcher.cpp | 4 +-- .../src/concave_hull_mask_image.cpp | 2 +- jsk_perception/src/consensus_tracking.cpp | 4 +-- jsk_perception/src/draw_rects.cpp | 8 ++--- .../src/dual_fisheye_to_panorama.cpp | 2 +- .../src/filter_mask_image_with_size.cpp | 6 ++-- jsk_perception/src/fisheye_to_panorama.cpp | 2 +- .../src/flow_velocity_thresholding.cpp | 6 ++-- jsk_perception/src/gaussian_blur.cpp | 2 +- jsk_perception/src/grabcut_nodelet.cpp | 4 +-- jsk_perception/src/grid_label.cpp | 2 +- jsk_perception/src/kmeans.cpp | 2 +- jsk_perception/src/label_to_mask_image.cpp | 2 +- jsk_perception/src/mask_image_generator.cpp | 2 +- jsk_perception/src/mask_image_to_rect.cpp | 2 +- jsk_perception/src/morphological_operator.cpp | 2 +- jsk_perception/src/multiply_mask_image.cpp | 4 +-- .../src/overlay_image_color_on_mono.cpp | 6 ++-- jsk_perception/src/point_pose_extractor.cpp | 2 +- .../src/polygon_array_color_histogram.cpp | 4 +-- .../src/polygon_array_color_likelihood.cpp | 6 ++-- jsk_perception/src/project_image_point.cpp | 2 +- .../src/rect_array_actual_size_filter.cpp | 6 ++-- .../src/rect_array_to_density_image.cpp | 4 +-- jsk_perception/src/rectangle_detector.cpp | 4 +-- jsk_perception/src/remove_blurred_frames.cpp | 2 +- .../src/single_channel_histogram.cpp | 4 +-- jsk_perception/src/slic_superpixels.cpp | 2 +- .../src/sliding_window_object_detector.cpp | 2 +- jsk_perception/src/snake_segmentation.cpp | 2 +- jsk_perception/src/sparse_image_decoder.cpp | 4 +-- jsk_perception/src/sparse_image_encoder.cpp | 4 +-- jsk_perception/src/subtract_mask_image.cpp | 4 +-- .../tabletop_color_difference_likelihood.cpp | 4 +-- jsk_perception/src/unapply_mask_image.cpp | 4 +-- jsk_perception/src/video_to_scene.cpp | 2 +- jsk_perception/src/virtual_camera_mono.cpp | 2 +- orbit_pantilt/src/orbit_pantilt.cpp | 2 +- .../src/image_resizer_nodelet.cpp | 2 +- .../src/log_polar_nodelet.cpp | 2 +- 171 files changed, 333 insertions(+), 333 deletions(-) diff --git a/checkerboard_detector/src/checkerboard_detector.cpp b/checkerboard_detector/src/checkerboard_detector.cpp index c52893bd1f..bab567a8f4 100644 --- a/checkerboard_detector/src/checkerboard_detector.cpp +++ b/checkerboard_detector/src/checkerboard_detector.cpp @@ -136,7 +136,7 @@ class CheckerboardDetector srv = boost::make_shared > (_node); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&CheckerboardDetector::configCallback, this, _1, _2); + boost::bind (&CheckerboardDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv->setCallback (f); while(1) { diff --git a/checkerboard_detector/src/objectdetection_transform_echo.cpp b/checkerboard_detector/src/objectdetection_transform_echo.cpp index cb5bd21925..2aca65eb82 100644 --- a/checkerboard_detector/src/objectdetection_transform_echo.cpp +++ b/checkerboard_detector/src/objectdetection_transform_echo.cpp @@ -142,7 +142,7 @@ int main(int argc, char** argv) message_filters::Synchronizer sync( SyncPolicy(1000), detection1_sub, detection2_sub); - sync.registerCallback(boost::bind(&callback, _1, _2)); + sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2)); ros::spin(); return 0; } diff --git a/cr_capture/src/cr_node.cpp b/cr_capture/src/cr_node.cpp index 6a6648e77f..80d636b4ac 100644 --- a/cr_capture/src/cr_node.cpp +++ b/cr_capture/src/cr_node.cpp @@ -73,7 +73,7 @@ class CRCaptureNode { CRCaptureNode () : nh_("~"), it_(nh_), sync_(5) { // Set up dynamic reconfiguration - ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, _1, _2); + ReconfigureServer::CallbackType f = boost::bind(&CRCaptureNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_.setCallback(f); // parameter @@ -171,7 +171,7 @@ class CRCaptureNode { info_sub_.subscribe(nh_, range_ns_ + "/camera_info", 1); sync_.connectInput(image_conf_sub_, image_intent_sub_, image_depth_sub_, info_sub_); - sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, _1, _2, _3, _4)); + sync_.registerCallback(boost::bind(&CRCaptureNode::cameraallCB, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } else { // not all subscribe camera_sub_depth_ = it_.subscribeCamera(range_ns_ + "/image", 1, &CRCaptureNode::camerarangeCB, this); diff --git a/cr_capture/src/cr_node_sync.cpp b/cr_capture/src/cr_node_sync.cpp index d6558c80f2..850ff65af5 100644 --- a/cr_capture/src/cr_node_sync.cpp +++ b/cr_capture/src/cr_node_sync.cpp @@ -76,7 +76,7 @@ class CRCaptureSyncNode { CRCaptureSyncNode () : nh_("~"), it_(nh_), sync_(30) { // Set up dynamic reconfiguration - ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, _1, _2); + ReconfigureServer::CallbackType f = boost::bind(&CRCaptureSyncNode::config_cb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_.setCallback(f); // parameter @@ -175,7 +175,7 @@ class CRCaptureSyncNode { sync_.connectInput(image_sub_left_, info_sub_left_, image_sub_right_, info_sub_right_, image_sub_confi_, image_sub_intent_, image_sub_depth_, info_sub_range_); - sync_.registerCallback(boost::bind(&CRCaptureSyncNode::imageCB, this, _1, _2, _3, _4, _5, _6, _7, _8)); + 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)); // pull raw data service nh_.param("pull_raw_data", pull_raw_data, false); diff --git a/imagesift/src/imagesift.cpp b/imagesift/src/imagesift.cpp index eb77b69a96..b26cd1994e 100644 --- a/imagesift/src/imagesift.cpp +++ b/imagesift/src/imagesift.cpp @@ -92,7 +92,7 @@ namespace imagesift _subMask.subscribe(*nh_, "mask", 1); _sync = boost::make_shared >(100); _sync->connectInput(_subImageWithMask, _subMask); - _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2)); + _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, boost::placeholders::_1, boost::placeholders::_2)); } _subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this); } diff --git a/jsk_libfreenect2/src/driver_nodelet.cpp b/jsk_libfreenect2/src/driver_nodelet.cpp index 800a3fdeba..69bf226018 100644 --- a/jsk_libfreenect2/src/driver_nodelet.cpp +++ b/jsk_libfreenect2/src/driver_nodelet.cpp @@ -37,7 +37,7 @@ namespace jsk_libfreenect2 glfwInit(); timer_ = getNodeHandle().createTimer( ros::Duration(5.0), - boost::bind(&Driver::run, this, _1), true); + boost::bind(&Driver::run, this, boost::placeholders::_1), true); } void Driver::run(const ros::TimerEvent&) { diff --git a/jsk_pcl_ros/src/add_color_from_image_nodelet.cpp b/jsk_pcl_ros/src/add_color_from_image_nodelet.cpp index 84475a1007..e77d87fc71 100644 --- a/jsk_pcl_ros/src/add_color_from_image_nodelet.cpp +++ b/jsk_pcl_ros/src/add_color_from_image_nodelet.cpp @@ -70,7 +70,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_cloud_, sub_image_, sub_info_); sync_->registerCallback(boost::bind(&AddColorFromImage::addColor, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void AddColorFromImage::unsubscribe() diff --git a/jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp b/jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp index edd2a9a561..f53e632f7e 100644 --- a/jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp +++ b/jsk_pcl_ros/src/add_color_from_image_to_organized_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros sub_image_.subscribe(*pnh_, "input/image", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_cloud_, sub_image_); - sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, _1, _2)); + sync_->registerCallback(boost::bind(&AddColorFromImageToOrganized::addColor, this, boost::placeholders::_1, boost::placeholders::_2)); } void AddColorFromImageToOrganized::unsubscribe() diff --git a/jsk_pcl_ros/src/bilateral_filter_nodelet.cpp b/jsk_pcl_ros/src/bilateral_filter_nodelet.cpp index e57bb28fdb..bd2e4d71cf 100644 --- a/jsk_pcl_ros/src/bilateral_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/bilateral_filter_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&BilateralFilter::configCallback, this, _1, _2); + boost::bind (&BilateralFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/border_estimator_nodelet.cpp b/jsk_pcl_ros/src/border_estimator_nodelet.cpp index 85c6e9f6ef..0c0c829a0d 100644 --- a/jsk_pcl_ros/src/border_estimator_nodelet.cpp +++ b/jsk_pcl_ros/src/border_estimator_nodelet.cpp @@ -50,7 +50,7 @@ namespace jsk_pcl_ros pnh_->param("model_type", model_type_, std::string("planar")); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&BorderEstimator::configCallback, this, _1, _2); + boost::bind (&BorderEstimator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_border_ = advertise(*pnh_, "output_border_indices", 1); @@ -82,7 +82,7 @@ namespace jsk_pcl_ros sub_camera_info_.subscribe(*pnh_, "input_camera_info", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_point_, sub_camera_info_); - sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, _1, _2)); + sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, boost::placeholders::_1, boost::placeholders::_2)); } else if (model_type_ == "laser") { sub_ = pnh_->subscribe("input", 1, &BorderEstimator::estimate, this); diff --git a/jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp b/jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp index deb22ac3c8..4a2128082d 100644 --- a/jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/bounding_box_filter_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &BoundingBoxFilter::configCallback, this, _1, _2); + &BoundingBoxFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //////////////////////////////////////////////////////// @@ -82,9 +82,9 @@ namespace jsk_pcl_ros sub_indices_.subscribe(*pnh_, "input_indices", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_box_, sub_indices_); - sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, _1, _2)); + sync_->registerCallback(boost::bind(&BoundingBoxFilter::filterWithIndices, this, boost::placeholders::_1, boost::placeholders::_2)); } else { - sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, _1)); + sub_box_.registerCallback(boost::bind(&BoundingBoxFilter::filter, this, boost::placeholders::_1)); } } diff --git a/jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp b/jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp index 7f9177a4ae..5bccd0977a 100644 --- a/jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp +++ b/jsk_pcl_ros/src/capture_stereo_synchronizer_nodelet.cpp @@ -117,11 +117,11 @@ namespace jsk_pcl_ros sub_disparity_); sync_->registerCallback(boost::bind(&CaptureStereoSynchronizer::republish, this, - _1, - _2, - _3, - _4, - _5, + boost::placeholders::_1, + boost::placeholders::_2, + boost::placeholders::_3, + boost::placeholders::_4, + boost::placeholders::_5, _6, _7)); } diff --git a/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp b/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp index 8494d4a8c4..c085e1caec 100644 --- a/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp +++ b/jsk_pcl_ros/src/cluster_point_indices_decomposer_nodelet.cpp @@ -120,7 +120,7 @@ namespace jsk_pcl_ros // dynamic_reconfigure srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, _1, _2); + boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); negative_indices_pub_ = advertise(*pnh_, "negative_indices", 1); @@ -153,24 +153,24 @@ namespace jsk_pcl_ros if (use_async_) { async_align_ = boost::make_shared >(queue_size_); async_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_); - async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4)); + async_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } else { sync_align_ = boost::make_shared >(queue_size_); sync_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_); - sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4)); + sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } } else { if (use_async_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_input_, sub_target_); - async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2)); + async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_input_, sub_target_); - sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2)); + sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, boost::placeholders::_1, boost::placeholders::_2)); } } } diff --git a/jsk_pcl_ros/src/color_based_region_growing_segmentation_nodelet.cpp b/jsk_pcl_ros/src/color_based_region_growing_segmentation_nodelet.cpp index ab5db395c4..3d87c19e9a 100644 --- a/jsk_pcl_ros/src/color_based_region_growing_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/color_based_region_growing_segmentation_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f= - boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, _1, _2); + boost::bind (&ColorBasedRegionGrowingSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/color_filter_nodelet.cpp b/jsk_pcl_ros/src/color_filter_nodelet.cpp index 4f5fd9aa38..59abd66e48 100644 --- a/jsk_pcl_ros/src/color_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/color_filter_nodelet.cpp @@ -342,7 +342,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ColorFilter::configCallback, this, _1, _2); + boost::bind (&ColorFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); @@ -356,7 +356,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(10); sub_indices_.subscribe(*pnh_, "indices", 1); sync_->connectInput(sub_input_, sub_indices_); - sync_->registerCallback(boost::bind(&ColorFilter::filter, this, _1, _2)); + sync_->registerCallback(boost::bind(&ColorFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2)); //sub_input_ = pnh_->subscribe("input", 1, &RGBColorFilter::filter, this); } else { diff --git a/jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp b/jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp index 8354cb5d7b..240eb98134 100644 --- a/jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp +++ b/jsk_pcl_ros/src/color_histogram_classifier_nodelet.cpp @@ -52,7 +52,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ColorHistogramClassifier::configCallback, this, _1, _2); + boost::bind(&ColorHistogramClassifier::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_class_ = advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/color_histogram_filter_nodelet.cpp b/jsk_pcl_ros/src/color_histogram_filter_nodelet.cpp index 2d6146ebe5..e8cd602288 100644 --- a/jsk_pcl_ros/src/color_histogram_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/color_histogram_filter_nodelet.cpp @@ -53,7 +53,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ColorHistogramFilter::configCallback, this, _1, _2); + boost::bind(&ColorHistogramFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_histogram_ = advertise(*pnh_, "output", 1); pub_indices_ = advertise(*pnh_, "output/indices", 1); @@ -94,7 +94,7 @@ namespace jsk_pcl_ros sub_indices_.subscribe(*pnh_, "input/indices", 1); sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_histogram_, sub_indices_); - sync_->registerCallback(boost::bind(&ColorHistogramFilter::feature, this, _1, _2)); + sync_->registerCallback(boost::bind(&ColorHistogramFilter::feature, this, boost::placeholders::_1, boost::placeholders::_2)); } void ColorHistogramFilter::unsubscribe() diff --git a/jsk_pcl_ros/src/color_histogram_matcher_nodelet.cpp b/jsk_pcl_ros/src/color_histogram_matcher_nodelet.cpp index 2d86619d9d..50901779b1 100644 --- a/jsk_pcl_ros/src/color_histogram_matcher_nodelet.cpp +++ b/jsk_pcl_ros/src/color_histogram_matcher_nodelet.cpp @@ -53,7 +53,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ColorHistogramMatcher::configCallback, this, _1, _2); + boost::bind (&ColorHistogramMatcher::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); policy_ = USE_HUE_AND_SATURATION; @@ -98,7 +98,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_indices_); sync_->registerCallback(boost::bind(&ColorHistogramMatcher::feature, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void ColorHistogramMatcher::unsubscribe() diff --git a/jsk_pcl_ros/src/color_histogram_nodelet.cpp b/jsk_pcl_ros/src/color_histogram_nodelet.cpp index 03d4e9daa8..e3fb2db5d9 100644 --- a/jsk_pcl_ros/src/color_histogram_nodelet.cpp +++ b/jsk_pcl_ros/src/color_histogram_nodelet.cpp @@ -54,7 +54,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ColorHistogram::configCallback, this, _1, _2); + boost::bind(&ColorHistogram::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_histogram_ = advertise(*pnh_, "output", 1); onInitPostProcess(); @@ -94,7 +94,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_cloud_, sub_indices_); sync_->registerCallback(boost::bind(&ColorHistogram::feature, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void ColorHistogram::unsubscribe() diff --git a/jsk_pcl_ros/src/container_occupancy_detector_nodelet.cpp b/jsk_pcl_ros/src/container_occupancy_detector_nodelet.cpp index 9ed09c4db1..0858dce925 100644 --- a/jsk_pcl_ros/src/container_occupancy_detector_nodelet.cpp +++ b/jsk_pcl_ros/src/container_occupancy_detector_nodelet.cpp @@ -73,11 +73,11 @@ namespace jsk_pcl_ros{ if(approximate_sync_){ ap_sync_ = std::make_shared >(queue_size_); ap_sync_ -> connectInput(sub_boxes_, sub_points_, sub_point_indices_); - ap_sync_ -> registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, _1, _2, _3)); + ap_sync_ -> registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); }else{ sync_ = std::make_shared >(100); sync_->connectInput(sub_boxes_, sub_points_, sub_point_indices_); - sync_->registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, _1, _2, _3)); + sync_->registerCallback(boost::bind(&ContainerOccupancyDetector::calculate, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } } diff --git a/jsk_pcl_ros/src/depth_calibration_nodelet.cpp b/jsk_pcl_ros/src/depth_calibration_nodelet.cpp index 1122cc85e0..15b7dd5b46 100644 --- a/jsk_pcl_ros/src/depth_calibration_nodelet.cpp +++ b/jsk_pcl_ros/src/depth_calibration_nodelet.cpp @@ -122,7 +122,7 @@ namespace jsk_pcl_ros sub_camera_info_.subscribe(*pnh_, "camera_info", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_camera_info_); - sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, _1, _2)); + sync_->registerCallback(boost::bind(&DepthCalibration::calibrate, this, boost::placeholders::_1, boost::placeholders::_2)); } void DepthCalibration::unsubscribe() diff --git a/jsk_pcl_ros/src/depth_image_creator_nodelet.cpp b/jsk_pcl_ros/src/depth_image_creator_nodelet.cpp index 4673452ce8..a4674f45a3 100644 --- a/jsk_pcl_ros/src/depth_image_creator_nodelet.cpp +++ b/jsk_pcl_ros/src/depth_image_creator_nodelet.cpp @@ -132,11 +132,11 @@ void jsk_pcl_ros::DepthImageCreator::subscribe() { if (use_approximate) { sync_inputs_a_ = boost::make_shared > > (max_queue_size_); sync_inputs_a_->connectInput (sub_info_, sub_cloud_); - sync_inputs_a_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2)); + sync_inputs_a_->registerCallback (bind (&DepthImageCreator::callback_sync, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_inputs_e_ = boost::make_shared > > (max_queue_size_); sync_inputs_e_->connectInput (sub_info_, sub_cloud_); - sync_inputs_e_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2)); + sync_inputs_e_->registerCallback (bind (&DepthImageCreator::callback_sync, this, boost::placeholders::_1, boost::placeholders::_2)); } } } else { diff --git a/jsk_pcl_ros/src/edge_depth_refinement_nodelet.cpp b/jsk_pcl_ros/src/edge_depth_refinement_nodelet.cpp index 41ce799c12..d2da3467c1 100644 --- a/jsk_pcl_ros/src/edge_depth_refinement_nodelet.cpp +++ b/jsk_pcl_ros/src/edge_depth_refinement_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&EdgeDepthRefinement::configCallback, this, _1, _2); + boost::bind (&EdgeDepthRefinement::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); @@ -94,7 +94,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_indices_); sync_->registerCallback(boost::bind(&EdgeDepthRefinement::refine, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void EdgeDepthRefinement::unsubscribe() diff --git a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp index 400610d98f..a894179c5c 100644 --- a/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp @@ -381,7 +381,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&EdgebasedCubeFinder::configCallback, this, _1, _2); + boost::bind (&EdgebasedCubeFinder::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); @@ -424,7 +424,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_edges_); sync_->registerCallback(boost::bind( - &EdgebasedCubeFinder::estimate, this, _1, _2)); + &EdgebasedCubeFinder::estimate, this, boost::placeholders::_1, boost::placeholders::_2)); } void EdgebasedCubeFinder::unsubscribe() diff --git a/jsk_pcl_ros/src/environment_plane_modeling_nodelet.cpp b/jsk_pcl_ros/src/environment_plane_modeling_nodelet.cpp index 4052a849de..5c6e2145f5 100644 --- a/jsk_pcl_ros/src/environment_plane_modeling_nodelet.cpp +++ b/jsk_pcl_ros/src/environment_plane_modeling_nodelet.cpp @@ -57,7 +57,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&EnvironmentPlaneModeling::configCallback, this, _1, _2); + boost::bind (&EnvironmentPlaneModeling::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("complete_footprint_region", complete_footprint_region_, false); @@ -110,7 +110,7 @@ namespace jsk_pcl_ros sub_coefficients_, sub_indices_); sync_->registerCallback( boost::bind(&EnvironmentPlaneModeling::inputCallback, - this, _1, _2, _3, _4, _5)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5)); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp index 3669bb06b3..d2d2fd0301 100644 --- a/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp +++ b/jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp @@ -392,7 +392,7 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&EuclideanClustering::configCallback, this, _1, _2); + boost::bind (&EuclideanClustering::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //////////////////////////////////////////////////////// @@ -429,11 +429,11 @@ namespace jsk_pcl_ros if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_cluster_indices_, sub_point_cloud_); - async_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, _1, _2)); + async_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_cluster_indices_, sub_point_cloud_); - sync_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, _1, _2)); + sync_->registerCallback(boost::bind(&EuclideanClustering::multi_extract, this, boost::placeholders::_1, boost::placeholders::_2)); } } else { sub_input_ = pnh_->subscribe("input", 1, &EuclideanClustering::extract, this); diff --git a/jsk_pcl_ros/src/extract_cuboid_particles_top_n_nodelet.cpp b/jsk_pcl_ros/src/extract_cuboid_particles_top_n_nodelet.cpp index c4fb72d2d6..f613004299 100644 --- a/jsk_pcl_ros/src/extract_cuboid_particles_top_n_nodelet.cpp +++ b/jsk_pcl_ros/src/extract_cuboid_particles_top_n_nodelet.cpp @@ -46,7 +46,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ExtractCuboidParticlesTopN::configCallback, this, _1, _2); + boost::bind (&ExtractCuboidParticlesTopN::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); pub_pose_array_ = advertise(*pnh_, "output/pose_array", 1); diff --git a/jsk_pcl_ros/src/extract_indices_nodelet.cpp b/jsk_pcl_ros/src/extract_indices_nodelet.cpp index 094b34b109..eaae81a062 100644 --- a/jsk_pcl_ros/src/extract_indices_nodelet.cpp +++ b/jsk_pcl_ros/src/extract_indices_nodelet.cpp @@ -78,13 +78,13 @@ namespace jsk_pcl_ros async_ = boost::make_shared >(100); async_->connectInput(sub_indices_, sub_cloud_); async_->registerCallback( - boost::bind(&ExtractIndices::convert, this, _1, _2)); + boost::bind(&ExtractIndices::convert, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_indices_, sub_cloud_); sync_->registerCallback( - boost::bind(&ExtractIndices::convert, this, _1, _2)); + boost::bind(&ExtractIndices::convert, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros/src/feature_registration_nodelet.cpp b/jsk_pcl_ros/src/feature_registration_nodelet.cpp index b60e4e07af..0f57c703eb 100644 --- a/jsk_pcl_ros/src/feature_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/feature_registration_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&FeatureRegistration::configCallback, this, _1, _2); + boost::bind (&FeatureRegistration::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); @@ -60,7 +60,7 @@ namespace jsk_pcl_ros reference_sync_->connectInput( sub_input_reference_, sub_input_reference_feature_); reference_sync_->registerCallback(boost::bind(&FeatureRegistration::referenceCallback, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); pub_pose_ = advertise(*pnh_, "output", 1); pub_cloud_ = advertise(*pnh_, "output/cloud", 1); onInitPostProcess(); @@ -86,7 +86,7 @@ namespace jsk_pcl_ros sync_->connectInput( sub_input_, sub_input_feature_); sync_->registerCallback(boost::bind(&FeatureRegistration::estimate, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void FeatureRegistration::unsubscribe() diff --git a/jsk_pcl_ros/src/find_object_on_plane_nodelet.cpp b/jsk_pcl_ros/src/find_object_on_plane_nodelet.cpp index 955d1da30a..bf7fbd5aca 100644 --- a/jsk_pcl_ros/src/find_object_on_plane_nodelet.cpp +++ b/jsk_pcl_ros/src/find_object_on_plane_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_image_, sub_info_, sub_coefficients_); sync_->registerCallback(boost::bind(&FindObjectOnPlane::find, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void FindObjectOnPlane::unsubscribe() diff --git a/jsk_pcl_ros/src/fisheye_sphere_publisher_nodelet.cpp b/jsk_pcl_ros/src/fisheye_sphere_publisher_nodelet.cpp index 9f9ef6de0e..fd21eaaf41 100644 --- a/jsk_pcl_ros/src/fisheye_sphere_publisher_nodelet.cpp +++ b/jsk_pcl_ros/src/fisheye_sphere_publisher_nodelet.cpp @@ -110,7 +110,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&FisheyeSpherePublisher::configCallback, this, _1, _2); + boost::bind (&FisheyeSpherePublisher::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/fuse_images.cpp b/jsk_pcl_ros/src/fuse_images.cpp index 1592842561..81815c8179 100644 --- a/jsk_pcl_ros/src/fuse_images.cpp +++ b/jsk_pcl_ros/src/fuse_images.cpp @@ -109,7 +109,7 @@ namespace jsk_pcl_ros } // Bogus null filter - filters_[0]->registerCallback(bind(&FuseDepthImages::input_callback, this, _1)); + filters_[0]->registerCallback(bind(&FuseDepthImages::input_callback, this, boost::placeholders::_1)); if (input_topics.size() == 2) { @@ -202,11 +202,11 @@ namespace jsk_pcl_ros if (approximate_sync_) { - async_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, _1, _2, _3, _4, _5, _6, _7, _8)); + async_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, _6, _7, _8)); } else { - sync_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, _1, _2, _3, _4, _5, _6, _7, _8)); + sync_->registerCallback(boost::bind(&FuseDepthImages::inputCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, _6, _7, _8)); } } diff --git a/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp b/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp index f0720e8d3a..f106e72b04 100644 --- a/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp +++ b/jsk_pcl_ros/src/geometric_consistency_grouping_nodelet.cpp @@ -46,7 +46,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&GeometricConsistencyGrouping::configCallback, this, _1, _2); + boost::bind (&GeometricConsistencyGrouping::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_output_ = advertise(*pnh_, "output", 1); pub_output_cloud_ = advertise(*pnh_, "output/cloud", 1); @@ -57,7 +57,7 @@ namespace jsk_pcl_ros reference_sync_->connectInput(sub_reference_cloud_, sub_reference_feature_); reference_sync_->registerCallback( boost::bind(&GeometricConsistencyGrouping::referenceCallback, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); onInitPostProcess(); } @@ -80,7 +80,7 @@ namespace jsk_pcl_ros sub_feature_.subscribe(*pnh_, "input/feature", 1); sync_->connectInput(sub_input_, sub_feature_); sync_->registerCallback(boost::bind(&GeometricConsistencyGrouping::recognize, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void GeometricConsistencyGrouping::unsubscribe() diff --git a/jsk_pcl_ros/src/grid_sampler_nodelet.cpp b/jsk_pcl_ros/src/grid_sampler_nodelet.cpp index 0b1ffb91c5..f29c97ca2c 100644 --- a/jsk_pcl_ros/src/grid_sampler_nodelet.cpp +++ b/jsk_pcl_ros/src/grid_sampler_nodelet.cpp @@ -45,7 +45,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); pub_ = advertise(*pnh_, "output", 1); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&GridSampler::configCallback, this, _1, _2); + boost::bind (&GridSampler::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_ = boost::make_shared > (*pnh_); srv_->setCallback (f); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/handle_estimator_nodelet.cpp b/jsk_pcl_ros/src/handle_estimator_nodelet.cpp index 2ba0908e03..d375b46941 100644 --- a/jsk_pcl_ros/src/handle_estimator_nodelet.cpp +++ b/jsk_pcl_ros/src/handle_estimator_nodelet.cpp @@ -74,12 +74,12 @@ namespace jsk_pcl_ros void HandleEstimator::subscribe() { - sub_index_ = pnh_->subscribe("selected_index", 1, boost::bind( &HandleEstimator::selectedIndexCallback, this, _1)); + sub_index_ = pnh_->subscribe("selected_index", 1, boost::bind( &HandleEstimator::selectedIndexCallback, this, boost::placeholders::_1)); sub_input_.subscribe(*pnh_, "input", 1); sub_box_.subscribe(*pnh_, "input_box", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_box_); - sync_->registerCallback(boost::bind(&HandleEstimator::estimate, this, _1, _2)); + sync_->registerCallback(boost::bind(&HandleEstimator::estimate, this, boost::placeholders::_1, boost::placeholders::_2)); } void HandleEstimator::unsubscribe() diff --git a/jsk_pcl_ros/src/heightmap_converter_nodelet.cpp b/jsk_pcl_ros/src/heightmap_converter_nodelet.cpp index c73bdd106b..5b45c08233 100644 --- a/jsk_pcl_ros/src/heightmap_converter_nodelet.cpp +++ b/jsk_pcl_ros/src/heightmap_converter_nodelet.cpp @@ -51,7 +51,7 @@ namespace jsk_pcl_ros "output/config", 1, true); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&HeightmapConverter::configCallback, this, _1, _2); + boost::bind (&HeightmapConverter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("fixed_frame_id", fixed_frame_id_, std::string("map")); diff --git a/jsk_pcl_ros/src/heightmap_morphological_filtering_nodelet.cpp b/jsk_pcl_ros/src/heightmap_morphological_filtering_nodelet.cpp index 42ac013a8f..8edcaf91ce 100644 --- a/jsk_pcl_ros/src/heightmap_morphological_filtering_nodelet.cpp +++ b/jsk_pcl_ros/src/heightmap_morphological_filtering_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros 1, true); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&HeightmapMorphologicalFiltering::configCallback, this, _1, _2); + boost::bind (&HeightmapMorphologicalFiltering::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("max_queue_size", max_queue_size_, 10); diff --git a/jsk_pcl_ros/src/heightmap_time_accumulation_nodelet.cpp b/jsk_pcl_ros/src/heightmap_time_accumulation_nodelet.cpp index eda3cffbdd..50021883e2 100644 --- a/jsk_pcl_ros/src/heightmap_time_accumulation_nodelet.cpp +++ b/jsk_pcl_ros/src/heightmap_time_accumulation_nodelet.cpp @@ -50,7 +50,7 @@ namespace jsk_pcl_ros "output/config", 1, true); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&HeightmapTimeAccumulation::configCallback, this, _1, _2); + boost::bind (&HeightmapTimeAccumulation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); sub_config_ = pnh_->subscribe( getHeightmapConfigTopic(pnh_->resolveName("input")), 1, @@ -79,7 +79,7 @@ namespace jsk_pcl_ros tf_queue_size)); tf_filter_->registerCallback( boost::bind( - &HeightmapTimeAccumulation::accumulate, this, _1)); + &HeightmapTimeAccumulation::accumulate, this, boost::placeholders::_1)); srv_reset_ = pnh_->advertiseService("reset", &HeightmapTimeAccumulation::resetCallback, this); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/hinted_handle_estimator_nodelet.cpp b/jsk_pcl_ros/src/hinted_handle_estimator_nodelet.cpp index f80b0ee5cf..facf951370 100644 --- a/jsk_pcl_ros/src/hinted_handle_estimator_nodelet.cpp +++ b/jsk_pcl_ros/src/hinted_handle_estimator_nodelet.cpp @@ -89,7 +89,7 @@ namespace jsk_pcl_ros sub_point_.subscribe(*pnh_, "point", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_cloud_, sub_point_); - sync_->registerCallback(boost::bind(&HintedHandleEstimator::estimate, this, _1, _2)); + sync_->registerCallback(boost::bind(&HintedHandleEstimator::estimate, this, boost::placeholders::_1, boost::placeholders::_2)); } void HintedHandleEstimator::unsubscribe() diff --git a/jsk_pcl_ros/src/hinted_plane_detector_nodelet.cpp b/jsk_pcl_ros/src/hinted_plane_detector_nodelet.cpp index 672edcab4f..9907bb59b2 100644 --- a/jsk_pcl_ros/src/hinted_plane_detector_nodelet.cpp +++ b/jsk_pcl_ros/src/hinted_plane_detector_nodelet.cpp @@ -54,7 +54,7 @@ namespace jsk_pcl_ros { DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&HintedPlaneDetector::configCallback, this, _1, _2); + boost::bind (&HintedPlaneDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_hint_polygon_ = advertise( @@ -102,7 +102,7 @@ namespace jsk_pcl_ros { sync_ = boost::make_shared >(100); sync_->connectInput(sub_cloud_, sub_hint_cloud_); sync_->registerCallback(boost::bind(&HintedPlaneDetector::detect, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void HintedPlaneDetector::unsubscribe() diff --git a/jsk_pcl_ros/src/hinted_stick_finder_nodelet.cpp b/jsk_pcl_ros/src/hinted_stick_finder_nodelet.cpp index 971848d4f5..2004dbc4c7 100644 --- a/jsk_pcl_ros/src/hinted_stick_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/hinted_stick_finder_nodelet.cpp @@ -51,7 +51,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&HintedStickFinder::configCallback, this, _1, _2); + boost::bind (&HintedStickFinder::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("use_normal", use_normal_, false); pnh_->param("not_synchronize", not_synchronize_, false); @@ -91,7 +91,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_polygon_, sub_info_, sub_cloud_); sync_->registerCallback(boost::bind(&HintedStickFinder::detect, this, - _1, _2, _3)); + boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sub_no_sync_cloud_ = pnh_->subscribe( diff --git a/jsk_pcl_ros/src/icp_registration_nodelet.cpp b/jsk_pcl_ros/src/icp_registration_nodelet.cpp index dab748f232..d4e3fd350f 100644 --- a/jsk_pcl_ros/src/icp_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/icp_registration_nodelet.cpp @@ -62,7 +62,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind( - &ICPRegistration::configCallback, this, _1, _2); + &ICPRegistration::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("use_normal", use_normal_, false); pnh_->param("align_box", align_box_, false); @@ -137,14 +137,14 @@ namespace jsk_pcl_ros sync_->connectInput(sub_input_, sub_box_); sync_->registerCallback(boost::bind( &ICPRegistration::alignWithBox, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else if (use_offset_pose_) { sub_input_.subscribe(*pnh_, "input", 1); sub_offset_.subscribe(*pnh_, "input_offset", 1); sync_offset_ = boost::make_shared >(100); sync_offset_->connectInput(sub_input_, sub_offset_); - sync_offset_->registerCallback(boost::bind(&ICPRegistration::alignWithOffset, this, _1, _2)); + sync_offset_->registerCallback(boost::bind(&ICPRegistration::alignWithOffset, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_ = pnh_->subscribe("input", 1, @@ -157,7 +157,7 @@ namespace jsk_pcl_ros sub_sync_reference_.subscribe(*pnh_, "reference", 1); sync_reference_ = boost::make_shared >(100); sync_reference_->connectInput(sub_sync_input_, sub_sync_reference_); - sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, _1, _2)); + sync_reference_->registerCallback(boost::bind(&ICPRegistration::align, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros/src/image_rotate_nodelet.cpp b/jsk_pcl_ros/src/image_rotate_nodelet.cpp index 2b5ce3bad3..2961451dbc 100644 --- a/jsk_pcl_ros/src/image_rotate_nodelet.cpp +++ b/jsk_pcl_ros/src/image_rotate_nodelet.cpp @@ -331,12 +331,12 @@ class ImageRotateNodelet : public nodelet::Nodelet subscriber_count_ = 0; angle_ = 0; prev_stamp_ = ros::Time(0, 0); - image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ImageRotateNodelet::connectCb, this, _1); - image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&ImageRotateNodelet::disconnectCb, this, _1); + image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ImageRotateNodelet::connectCb, this, boost::placeholders::_1); + image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&ImageRotateNodelet::disconnectCb, this, boost::placeholders::_1); img_pub_ = image_transport::ImageTransport(ros::NodeHandle(nh_, "rotated")).advertise("image", 1, connect_cb, disconnect_cb); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ImageRotateNodelet::reconfigureCallback, this, _1, _2); + boost::bind(&ImageRotateNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv.setCallback(f); } }; diff --git a/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp b/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp index 6a1226655f..8e71182b0a 100644 --- a/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/incremental_model_registration_nodelet.cpp @@ -110,7 +110,7 @@ namespace jsk_pcl_ros sync_->connectInput(sub_cloud_, sub_indices_, sub_pose_); sync_->registerCallback(boost::bind( &IncrementalModelRegistration::newsampleCallback, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/interactive_cuboid_likelihood_nodelet.cpp b/jsk_pcl_ros/src/interactive_cuboid_likelihood_nodelet.cpp index e8dc2c5dbc..326ee2bad8 100644 --- a/jsk_pcl_ros/src/interactive_cuboid_likelihood_nodelet.cpp +++ b/jsk_pcl_ros/src/interactive_cuboid_likelihood_nodelet.cpp @@ -68,20 +68,20 @@ namespace jsk_pcl_ros particle_.pitch = initial_rot[1]; particle_.yaw = initial_rot[2]; typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&InteractiveCuboidLikelihood::configCallback, this, _1, _2); + boost::bind (&InteractiveCuboidLikelihood::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); sub_ = pnh_->subscribe("input", 1, &InteractiveCuboidLikelihood::likelihood, this); // Cuboid server_.reset(new interactive_markers::InteractiveMarkerServer(getName())); visualization_msgs::InteractiveMarker int_marker = particleToInteractiveMarker(particle_); - server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, _1)); + server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, boost::placeholders::_1)); server_->applyChanges(); // SupportPlane plane_server_.reset(new interactive_markers::InteractiveMarkerServer(getName() + "_plane")); plane_pose_ = Eigen::Affine3f::Identity(); visualization_msgs::InteractiveMarker plane_int_marker = planeInteractiveMarker(); - plane_server_->insert(plane_int_marker, boost::bind(&InteractiveCuboidLikelihood::processPlaneFeedback, this, _1)); + plane_server_->insert(plane_int_marker, boost::bind(&InteractiveCuboidLikelihood::processPlaneFeedback, this, boost::placeholders::_1)); plane_server_->applyChanges(); onInitPostProcess(); } @@ -157,7 +157,7 @@ namespace jsk_pcl_ros particle_.dz = config_.dz; if (server_) { visualization_msgs::InteractiveMarker int_marker = particleToInteractiveMarker(particle_); - server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, _1)); + server_->insert(int_marker, boost::bind(&InteractiveCuboidLikelihood::processFeedback, this, boost::placeholders::_1)); server_->applyChanges(); } } diff --git a/jsk_pcl_ros/src/kinfu_nodelet.cpp b/jsk_pcl_ros/src/kinfu_nodelet.cpp index cebd07c812..9fe1920b76 100644 --- a/jsk_pcl_ros/src/kinfu_nodelet.cpp +++ b/jsk_pcl_ros/src/kinfu_nodelet.cpp @@ -94,7 +94,7 @@ namespace jsk_pcl_ros pnh_->param("volume_size", volume_size_, pcl::device::kinfuLS::VOLUME_SIZE); srv_ = boost::make_shared >(*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind(&Kinfu::configCallback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind(&Kinfu::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); tf_listener_.reset(new tf::TransformListener()); @@ -182,13 +182,13 @@ namespace jsk_pcl_ros sub_color_.subscribe(*pnh_, "input/color", 1); sync_with_color_.reset(new message_filters::Synchronizer(queue_size)); sync_with_color_->connectInput(sub_camera_info_, sub_depth_, sub_color_); - sync_with_color_->registerCallback(boost::bind(&Kinfu::update, this, _1, _2, _3)); + sync_with_color_->registerCallback(boost::bind(&Kinfu::update, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_.reset(new message_filters::Synchronizer(queue_size)); sync_->connectInput(sub_camera_info_, sub_depth_); - sync_->registerCallback(boost::bind(&Kinfu::update, this, _1, _2)); + sync_->registerCallback(boost::bind(&Kinfu::update, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros/src/line_segment_collector_nodelet.cpp b/jsk_pcl_ros/src/line_segment_collector_nodelet.cpp index 1f25c5e083..d022f4fc39 100644 --- a/jsk_pcl_ros/src/line_segment_collector_nodelet.cpp +++ b/jsk_pcl_ros/src/line_segment_collector_nodelet.cpp @@ -128,7 +128,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&LineSegmentCollector::configCallback, this, _1, _2); + boost::bind (&LineSegmentCollector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); std::string rotate_type_str; @@ -188,7 +188,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_indices_, sub_coefficients_); sync_->registerCallback(boost::bind(&LineSegmentCollector::collect, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); sub_trigger_ = pnh_->subscribe("trigger", 1, &LineSegmentCollector::triggerCallback, this); } diff --git a/jsk_pcl_ros/src/line_segment_detector_nodelet.cpp b/jsk_pcl_ros/src/line_segment_detector_nodelet.cpp index 37b4b99c46..e90e31e599 100644 --- a/jsk_pcl_ros/src/line_segment_detector_nodelet.cpp +++ b/jsk_pcl_ros/src/line_segment_detector_nodelet.cpp @@ -137,7 +137,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (config_mutex_, *pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&LineSegmentDetector::configCallback, this, _1, _2); + boost::bind (&LineSegmentDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //////////////////////////////////////////////////////// @@ -184,13 +184,13 @@ namespace jsk_pcl_ros async_ = boost::make_shared >(100); async_->connectInput(sub_input_, sub_indices_); async_->registerCallback(boost::bind(&LineSegmentDetector::segment, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_indices_); sync_->registerCallback(boost::bind(&LineSegmentDetector::segment, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros/src/linemod_nodelet.cpp b/jsk_pcl_ros/src/linemod_nodelet.cpp index 81e1d0ac8d..3a8508831c 100644 --- a/jsk_pcl_ros/src/linemod_nodelet.cpp +++ b/jsk_pcl_ros/src/linemod_nodelet.cpp @@ -87,7 +87,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_indices_); sync_->registerCallback(boost::bind(&LINEMODTrainer::store, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_input_nonsync_ = pnh_->subscribe("input", 1, @@ -589,7 +589,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &LINEMODDetector::configCallback, this, _1, _2); + &LINEMODDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_cloud_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/mask_image_cluster_filter_nodelet.cpp b/jsk_pcl_ros/src/mask_image_cluster_filter_nodelet.cpp index d8a64b778c..ec96170253 100644 --- a/jsk_pcl_ros/src/mask_image_cluster_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/mask_image_cluster_filter_nodelet.cpp @@ -73,7 +73,7 @@ namespace jsk_pcl_ros sub_target_.subscribe(*pnh_, "target", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_target_); - sync_->registerCallback(boost::bind(&MaskImageClusterFilter::concat, this, _1, _2)); + sync_->registerCallback(boost::bind(&MaskImageClusterFilter::concat, this, boost::placeholders::_1, boost::placeholders::_2)); } void MaskImageClusterFilter::unsubscribe() diff --git a/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp b/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp index 9ed0e18e05..2a16f7dd95 100644 --- a/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp +++ b/jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp @@ -102,7 +102,7 @@ namespace jsk_pcl_ros pnh_->param("calc_normal", calc_normal_, true); srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&MovingLeastSquareSmoothing::configCallback, this, _1, _2); + boost::bind(&MovingLeastSquareSmoothing::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ =advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/multi_plane_extraction_nodelet.cpp b/jsk_pcl_ros/src/multi_plane_extraction_nodelet.cpp index 1a917227af..4b266a0cb5 100644 --- a/jsk_pcl_ros/src/multi_plane_extraction_nodelet.cpp +++ b/jsk_pcl_ros/src/multi_plane_extraction_nodelet.cpp @@ -81,7 +81,7 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&MultiPlaneExtraction::configCallback, this, _1, _2); + boost::bind (&MultiPlaneExtraction::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); } @@ -111,14 +111,14 @@ namespace jsk_pcl_ros sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1); } else { sub_polygons_.registerCallback( - boost::bind(&MultiPlaneExtraction::fillEmptyCoefficients, this, _1)); + boost::bind(&MultiPlaneExtraction::fillEmptyCoefficients, this, boost::placeholders::_1)); } if (use_indices_) { sub_indices_.subscribe(*pnh_, "indices", 1); } else { sub_polygons_.registerCallback( - boost::bind(&MultiPlaneExtraction::fillEmptyIndices, this, _1)); + boost::bind(&MultiPlaneExtraction::fillEmptyIndices, this, boost::placeholders::_1)); } if (use_async_) { @@ -136,7 +136,7 @@ namespace jsk_pcl_ros async_->connectInput(sub_input_, null_indices_, null_coefficients_, sub_polygons_); } } - async_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4)); + async_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } else { sync_ = boost::make_shared >(maximum_queue_size_); if (use_indices_) { @@ -152,7 +152,7 @@ namespace jsk_pcl_ros sync_->connectInput(sub_input_, null_indices_, null_coefficients_, sub_polygons_); } } - sync_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4)); + sync_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } } diff --git a/jsk_pcl_ros/src/multi_plane_sac_segmentation_nodelet.cpp b/jsk_pcl_ros/src/multi_plane_sac_segmentation_nodelet.cpp index a10d4ecdc7..326a58fa52 100644 --- a/jsk_pcl_ros/src/multi_plane_sac_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/multi_plane_sac_segmentation_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&MultiPlaneSACSegmentation::configCallback, this, _1, _2); + boost::bind (&MultiPlaneSACSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("use_normal", use_normal_, false); pnh_->param("use_clusters", use_clusters_, false); @@ -101,14 +101,14 @@ namespace jsk_pcl_ros sync_normal_imu_->registerCallback( boost::bind( &MultiPlaneSACSegmentation::segmentWithImu, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_imu_ = boost::make_shared >(100); sync_imu_->connectInput(sub_input_, sub_imu_); sync_imu_->registerCallback(boost::bind( &MultiPlaneSACSegmentation::segmentWithImu, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } else if (use_normal_) { @@ -117,7 +117,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_input_, sub_normal_); sync_->registerCallback(boost::bind(&MultiPlaneSACSegmentation::segment, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else if (use_clusters_) { NODELET_INFO("use clusters"); @@ -128,7 +128,7 @@ namespace jsk_pcl_ros sync_cluster_->connectInput(sub_input_, sub_clusters_); sync_cluster_->registerCallback( boost::bind(&MultiPlaneSACSegmentation::segmentWithClusters, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_ = pnh_->subscribe("input", 1, &MultiPlaneSACSegmentation::segment, this); diff --git a/jsk_pcl_ros/src/normal_direction_filter_nodelet.cpp b/jsk_pcl_ros/src/normal_direction_filter_nodelet.cpp index e1e1f7f52a..ef02289b66 100644 --- a/jsk_pcl_ros/src/normal_direction_filter_nodelet.cpp +++ b/jsk_pcl_ros/src/normal_direction_filter_nodelet.cpp @@ -60,7 +60,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &NormalDirectionFilter::configCallback, this, _1, _2); + &NormalDirectionFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("queue_size", queue_size_, 200); pub_ = advertise(*pnh_, "output", 1); @@ -95,7 +95,7 @@ namespace jsk_pcl_ros sub_imu_.subscribe(*pnh_, "input_imu", 1); sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_input_, sub_imu_); - sync_->registerCallback(boost::bind(&NormalDirectionFilter::filter, this, _1, _2)); + sync_->registerCallback(boost::bind(&NormalDirectionFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros/src/normal_estimation_integral_image_nodelet.cpp b/jsk_pcl_ros/src/normal_estimation_integral_image_nodelet.cpp index e16dc2652f..10a5bf285f 100644 --- a/jsk_pcl_ros/src/normal_estimation_integral_image_nodelet.cpp +++ b/jsk_pcl_ros/src/normal_estimation_integral_image_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&NormalEstimationIntegralImage::configCallback, this, _1, _2); + boost::bind (&NormalEstimationIntegralImage::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/normal_estimation_omp_nodelet.cpp b/jsk_pcl_ros/src/normal_estimation_omp_nodelet.cpp index 80ea353f7b..9da43b8c97 100644 --- a/jsk_pcl_ros/src/normal_estimation_omp_nodelet.cpp +++ b/jsk_pcl_ros/src/normal_estimation_omp_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros NODELET_DEBUG_STREAM("num_of_threads: " << num_of_threads_); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&NormalEstimationOMP::configCallback, this, _1, _2); + boost::bind (&NormalEstimationOMP::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); pub_with_xyz_ = advertise(*pnh_, "output_with_xyz", 1); diff --git a/jsk_pcl_ros/src/octomap_server_contact_nodelet.cpp b/jsk_pcl_ros/src/octomap_server_contact_nodelet.cpp index 5fb6dd675d..5b65e07c1a 100644 --- a/jsk_pcl_ros/src/octomap_server_contact_nodelet.cpp +++ b/jsk_pcl_ros/src/octomap_server_contact_nodelet.cpp @@ -102,7 +102,7 @@ namespace jsk_pcl_ros m_pointProximitySub = new message_filters::Subscriber (m_nh, "proximity_in", 5); m_tfPointProximitySub = new tf::MessageFilter (*m_pointProximitySub, m_tfListener, m_worldFrameId, 5); - m_tfPointProximitySub->registerCallback(boost::bind(&OctomapServerContact::insertProximityCallback, this, _1)); + m_tfPointProximitySub->registerCallback(boost::bind(&OctomapServerContact::insertProximityCallback, this, boost::placeholders::_1)); m_frontierPointCloudPub = m_nh.advertise("octomap_frontier_point_cloud_centers", 1, m_latchedTopics); m_fromarkerPub = m_nh.advertise("frontier_cells_vis_array", 1, m_latchedTopics); @@ -110,7 +110,7 @@ namespace jsk_pcl_ros m_contactSensorSub.subscribe(m_nh, "contact_sensors_in", 2); m_tfContactSensorSub.reset(new tf::MessageFilter ( m_contactSensorSub, m_tfListener, m_worldFrameId, 2)); - m_tfContactSensorSub->registerCallback(boost::bind(&OctomapServerContact::insertContactSensorCallback, this, _1)); + m_tfContactSensorSub->registerCallback(boost::bind(&OctomapServerContact::insertContactSensorCallback, this, boost::placeholders::_1)); initContactSensor(privateNh); } diff --git a/jsk_pcl_ros/src/octree_change_publisher_nodelet.cpp b/jsk_pcl_ros/src/octree_change_publisher_nodelet.cpp index e75f6759c5..ab9f60a43f 100644 --- a/jsk_pcl_ros/src/octree_change_publisher_nodelet.cpp +++ b/jsk_pcl_ros/src/octree_change_publisher_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&OctreeChangePublisher::config_callback, this, _1, _2); + boost::bind(&OctreeChangePublisher::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); octree_ = new pcl::octree::OctreePointCloudChangeDetector(resolution_); diff --git a/jsk_pcl_ros/src/octree_voxel_grid_nodelet.cpp b/jsk_pcl_ros/src/octree_voxel_grid_nodelet.cpp index 8b4612d065..42a8db4649 100644 --- a/jsk_pcl_ros/src/octree_voxel_grid_nodelet.cpp +++ b/jsk_pcl_ros/src/octree_voxel_grid_nodelet.cpp @@ -174,7 +174,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&OctreeVoxelGrid::configCallback, this, _1, _2); + boost::bind (&OctreeVoxelGrid::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_cloud_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/organized_edge_detector_nodelet.cpp b/jsk_pcl_ros/src/organized_edge_detector_nodelet.cpp index 59b08f2ef1..183f728612 100644 --- a/jsk_pcl_ros/src/organized_edge_detector_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_edge_detector_nodelet.cpp @@ -58,7 +58,7 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&OrganizedEdgeDetector::configCallback, this, _1, _2); + boost::bind (&OrganizedEdgeDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //////////////////////////////////////////////////////// // indices publishers diff --git a/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp b/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp index 77eb712fa9..7df9af2ad1 100644 --- a/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp @@ -78,13 +78,13 @@ namespace jsk_pcl_ros boost::bind( &OrganizedMultiPlaneSegmentation::updateDiagnosticNormalEstimation, this, - _1)); + boost::placeholders::_1)); diagnostic_updater_->add( getName() + "::PlaneSegmentation", boost::bind( &OrganizedMultiPlaneSegmentation::updateDiagnosticPlaneSegmentation, this, - _1)); + boost::placeholders::_1)); double vital_rate; pnh_->param("vital_rate", vital_rate, 1.0); normal_estimation_vital_checker_.reset( @@ -127,14 +127,14 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &OrganizedMultiPlaneSegmentation::configCallback, this, _1, _2); + &OrganizedMultiPlaneSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); diagnostics_timer_ = pnh_->createTimer( ros::Duration(1.0), boost::bind(&OrganizedMultiPlaneSegmentation::updateDiagnostics, this, - _1)); + boost::placeholders::_1)); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/organized_pass_through_nodelet.cpp b/jsk_pcl_ros/src/organized_pass_through_nodelet.cpp index d82aef19e8..286cbf36b6 100644 --- a/jsk_pcl_ros/src/organized_pass_through_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_pass_through_nodelet.cpp @@ -60,7 +60,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &OrganizedPassThrough::configCallback, this, _1, _2); + &OrganizedPassThrough::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp b/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp index 3b9771efb9..5e97e8721d 100644 --- a/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp +++ b/jsk_pcl_ros/src/organized_statistical_outlier_removal_nodelet.cpp @@ -55,7 +55,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &OrganizedStatisticalOutlierRemoval::configCallback, this, _1, _2); + &OrganizedStatisticalOutlierRemoval::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/parallel_edge_finder_nodelet.cpp b/jsk_pcl_ros/src/parallel_edge_finder_nodelet.cpp index 187e0dee6e..35d16dfe85 100644 --- a/jsk_pcl_ros/src/parallel_edge_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/parallel_edge_finder_nodelet.cpp @@ -54,7 +54,7 @@ namespace jsk_pcl_ros //////////////////////////////////////////////////////// srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ParallelEdgeFinder::configCallback, this, _1, _2); + boost::bind (&ParallelEdgeFinder::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); } @@ -80,7 +80,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(100); sync_->connectInput(sub_indices_, sub_coefficients_); sync_->registerCallback(boost::bind(&ParallelEdgeFinder::estimate, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void ParallelEdgeFinder::unsubscribe() diff --git a/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp b/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp index cfb791de98..54f7829015 100644 --- a/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp +++ b/jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp @@ -63,7 +63,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ParticleFilterTracking::config_callback, this, _1, _2); + boost::bind(&ParticleFilterTracking::config_callback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); int particle_num; @@ -204,7 +204,7 @@ namespace jsk_pcl_ros change_sync_->registerCallback( boost::bind( &ParticleFilterTracking::cloud_change_cb, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_ = pnh_->subscribe("input", 1, &ParticleFilterTracking::cloud_cb,this); @@ -217,7 +217,7 @@ namespace jsk_pcl_ros sync_->registerCallback( boost::bind( &ParticleFilterTracking::renew_model_with_box_topic_cb, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_update_model_ = pnh_->subscribe( diff --git a/jsk_pcl_ros/src/people_detection_nodelet.cpp b/jsk_pcl_ros/src/people_detection_nodelet.cpp index 4fad1029c9..4955dc123a 100644 --- a/jsk_pcl_ros/src/people_detection_nodelet.cpp +++ b/jsk_pcl_ros/src/people_detection_nodelet.cpp @@ -79,7 +79,7 @@ namespace jsk_pcl_ros { //////////////////////////////////////////////////////// srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PeopleDetection::configCallback, this, _1, _2); + boost::bind(&PeopleDetection::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); //////////////////////////////////////////////////////// diff --git a/jsk_pcl_ros/src/plane_supported_cuboid_estimator_nodelet.cpp b/jsk_pcl_ros/src/plane_supported_cuboid_estimator_nodelet.cpp index d6fb94491e..fc30ff10d5 100644 --- a/jsk_pcl_ros/src/plane_supported_cuboid_estimator_nodelet.cpp +++ b/jsk_pcl_ros/src/plane_supported_cuboid_estimator_nodelet.cpp @@ -54,7 +54,7 @@ namespace jsk_pcl_ros tf_ = TfListenerSingleton::getInstance(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PlaneSupportedCuboidEstimator::configCallback, this, _1, _2); + boost::bind (&PlaneSupportedCuboidEstimator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("sensor_frame", sensor_frame_, std::string("odom")); pub_result_ = pnh_->advertise("output/result", 1); @@ -76,7 +76,7 @@ namespace jsk_pcl_ros sub_coefficients_.subscribe(*pnh_, "input/coefficients", 10); sync_polygon_ = boost::make_shared >(100); sync_polygon_->connectInput(sub_polygon_, sub_coefficients_); - sync_polygon_->registerCallback(boost::bind(&PlaneSupportedCuboidEstimator::polygonCallback, this, _1, _2)); + sync_polygon_->registerCallback(boost::bind(&PlaneSupportedCuboidEstimator::polygonCallback, this, boost::placeholders::_1, boost::placeholders::_2)); sub_cloud_ = pnh_->subscribe("input", 1, &PlaneSupportedCuboidEstimator::cloudCallback, this); sub_fast_cloud_ = pnh_->subscribe("fast_input", 1, &PlaneSupportedCuboidEstimator::fastCloudCallback, this); @@ -192,8 +192,8 @@ namespace jsk_pcl_ros NODELET_INFO("initTracker"); pcl::PointCloud::Ptr particles = initParticles(); tracker_.reset(new pcl::tracking::ROSCollaborativeParticleFilterTracker); - tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, _1)); - tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, _1, _2)); + tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, boost::placeholders::_1)); + tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, boost::placeholders::_1, boost::placeholders::_2)); tracker_->setParticles(particles); tracker_->setParticleNum(particle_num_); } @@ -313,8 +313,8 @@ namespace jsk_pcl_ros ParticleCloud::Ptr particles = initParticles(); tracker_.reset(new pcl::tracking::ROSCollaborativeParticleFilterTracker); - tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, _1)); - tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, _1, _2)); + tracker_->setCustomSampleFunc(boost::bind(&PlaneSupportedCuboidEstimator::sample, this, boost::placeholders::_1)); + tracker_->setLikelihoodFunc(boost::bind(&PlaneSupportedCuboidEstimator::likelihood, this, boost::placeholders::_1, boost::placeholders::_2)); tracker_->setParticles(particles); tracker_->setParticleNum(particle_num_); support_plane_updated_ = false; diff --git a/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp index 602b0446d5..00754881c6 100644 --- a/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp @@ -100,7 +100,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind( - &PointcloudDatabaseServer::configCallback, this, _1, _2); + &PointcloudDatabaseServer::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->getParam("duration", duration_); } @@ -132,7 +132,7 @@ namespace jsk_pcl_ros boost::bind( &PointcloudDatabaseServer::timerCallback, this, - _1)); + boost::placeholders::_1)); } } diff --git a/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp index 27adc7b498..9857b2bd80 100644 --- a/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_localization_nodelet.cpp @@ -77,11 +77,11 @@ namespace jsk_pcl_ros // timer to publish cloud cloud_timer_ = pnh_->createTimer( ros::Duration(1.0 / cloud_rate), - boost::bind(&PointCloudLocalization::cloudTimerCallback, this, _1)); + boost::bind(&PointCloudLocalization::cloudTimerCallback, this, boost::placeholders::_1)); // timer to publish tf tf_timer_ = pnh_->createTimer( ros::Duration(1.0 / tf_rate), - boost::bind(&PointCloudLocalization::tfTimerCallback, this, _1)); + boost::bind(&PointCloudLocalization::tfTimerCallback, this, boost::placeholders::_1)); onInitPostProcess(); } diff --git a/jsk_pcl_ros/src/pointcloud_moveit_filter.cpp b/jsk_pcl_ros/src/pointcloud_moveit_filter.cpp index 3d22142894..6eef59314d 100644 --- a/jsk_pcl_ros/src/pointcloud_moveit_filter.cpp +++ b/jsk_pcl_ros/src/pointcloud_moveit_filter.cpp @@ -97,7 +97,7 @@ namespace jsk_pcl_ros tf_ = monitor_->getTFClient(); shape_mask_.reset(new point_containment_filter::ShapeMask()); shape_mask_->setTransformCallback( - boost::bind(&PointCloudMoveitFilter::getShapeTransform, this, _1, _2)); + boost::bind(&PointCloudMoveitFilter::getShapeTransform, this, boost::placeholders::_1, boost::placeholders::_2)); filtered_cloud_publisher_ = private_nh_.advertise( filtered_cloud_topic_, 10, false); return true; @@ -159,13 +159,13 @@ namespace jsk_pcl_ros point_cloud_filter_->registerCallback( boost::bind( &PointCloudMoveitFilter::cloudMsgCallback, - this, _1)); + this, boost::placeholders::_1)); } else { point_cloud_filter_->registerCallback( boost::bind( &PointCloudMoveitFilter::cloudMsgCallback, - this, _1)); + this, boost::placeholders::_1)); } ROS_INFO("Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(), @@ -177,12 +177,12 @@ namespace jsk_pcl_ros point_cloud_subscriber_->registerCallback( boost::bind( &PointCloudMoveitFilter::cloudMsgCallback, - this, _1)); + this, boost::placeholders::_1)); } else { point_cloud_subscriber_->registerCallback( boost::bind(&PointCloudMoveitFilter::cloudMsgCallback, - this, _1)); + this, boost::placeholders::_1)); } ROS_INFO("Listening to '%s'", point_cloud_topic_.c_str()); } diff --git a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp index 0c65cdfed1..71f8ce8ea0 100644 --- a/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp +++ b/jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp @@ -54,7 +54,7 @@ void PointcloudScreenpoint::onInit() dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PointcloudScreenpoint::configCallback, this, _1, _2); + boost::bind(&PointcloudScreenpoint::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); dyn_srv_->setCallback(f); srv_ = pnh_->advertiseService( @@ -101,25 +101,25 @@ void PointcloudScreenpoint::subscribe() mf::Synchronizer >(queue_size_); async_rect_->connectInput(points_sub_, rect_sub_); async_rect_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, boost::placeholders::_1, boost::placeholders::_2)); async_poly_ = boost::make_shared< mf::Synchronizer >(queue_size_); async_poly_->connectInput(points_sub_, rect_sub_); async_poly_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, boost::placeholders::_1, boost::placeholders::_2)); async_point_ = boost::make_shared< mf::Synchronizer >(queue_size_); async_point_->connectInput(points_sub_, point_sub_); async_point_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_point_cb, this, boost::placeholders::_1, boost::placeholders::_2)); async_point_array_ = boost::make_shared< mf::Synchronizer >(queue_size_); async_point_array_->connectInput(points_sub_, point_array_sub_); async_point_array_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, boost::placeholders::_1, boost::placeholders::_2)); } else { @@ -127,39 +127,39 @@ void PointcloudScreenpoint::subscribe() mf::Synchronizer >(queue_size_); sync_rect_->connectInput(points_sub_, rect_sub_); sync_rect_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, boost::placeholders::_1, boost::placeholders::_2)); sync_poly_ = boost::make_shared< mf::Synchronizer >(queue_size_); sync_poly_->connectInput(points_sub_, rect_sub_); sync_poly_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, boost::placeholders::_1, boost::placeholders::_2)); sync_point_ = boost::make_shared< mf::Synchronizer >(queue_size_); sync_point_->connectInput(points_sub_, point_sub_); sync_point_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_point_cb, this, boost::placeholders::_1, boost::placeholders::_2)); sync_point_array_ = boost::make_shared< mf::Synchronizer >(queue_size_); sync_point_array_->connectInput(points_sub_, point_array_sub_); sync_point_array_->registerCallback( - boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2)); + boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, boost::placeholders::_1, boost::placeholders::_2)); } } else { points_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::points_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::points_cb, this, boost::placeholders::_1)); rect_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::rect_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::rect_cb, this, boost::placeholders::_1)); poly_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::poly_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::poly_cb, this, boost::placeholders::_1)); point_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::point_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::point_cb, this, boost::placeholders::_1)); point_array_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::point_array_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::point_array_cb, this, boost::placeholders::_1)); } } @@ -217,7 +217,7 @@ bool PointcloudScreenpoint::screenpoint_cb ( bool need_unsubscribe = false; if (!points_sub_.getSubscriber()) { points_sub_.registerCallback( - boost::bind(&PointcloudScreenpoint::points_cb, this, _1)); + boost::bind(&PointcloudScreenpoint::points_cb, this, boost::placeholders::_1)); need_unsubscribe = true; } diff --git a/jsk_pcl_ros/src/ppf_registration_nodelet.cpp b/jsk_pcl_ros/src/ppf_registration_nodelet.cpp index 3a236b0bf1..eba48926d4 100644 --- a/jsk_pcl_ros/src/ppf_registration_nodelet.cpp +++ b/jsk_pcl_ros/src/ppf_registration_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PPFRegistration::configCallback, this, _1, _2); + boost::bind (&PPFRegistration::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_points_array_ = advertise(*pnh_, "output/points_array", 1); @@ -82,13 +82,13 @@ namespace jsk_pcl_ros { array_async_ = boost::make_shared >(queue_size_); array_async_->connectInput(sub_input_, sub_reference_array_); - array_async_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2)); + array_async_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, boost::placeholders::_1, boost::placeholders::_2)); } else { array_sync_ = boost::make_shared >(queue_size_); array_sync_->connectInput(sub_input_, sub_reference_array_); - array_sync_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, _1, _2)); + array_sync_->registerCallback(boost::bind(&PPFRegistration::ArrayRegistration, this, boost::placeholders::_1, boost::placeholders::_2)); } } else @@ -97,13 +97,13 @@ namespace jsk_pcl_ros { cloud_async_ = boost::make_shared >(queue_size_); cloud_async_->connectInput(sub_input_, sub_reference_cloud_); - cloud_async_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2)); + cloud_async_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, boost::placeholders::_1, boost::placeholders::_2)); } else { cloud_sync_ = boost::make_shared >(queue_size_); cloud_sync_->connectInput(sub_input_, sub_reference_cloud_); - cloud_sync_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, _1, _2)); + cloud_sync_->registerCallback(boost::bind(&PPFRegistration::CloudRegistration, this, boost::placeholders::_1, boost::placeholders::_2)); } } } diff --git a/jsk_pcl_ros/src/primitive_shape_classifier_nodelet.cpp b/jsk_pcl_ros/src/primitive_shape_classifier_nodelet.cpp index efb4595be3..98cb1031e3 100644 --- a/jsk_pcl_ros/src/primitive_shape_classifier_nodelet.cpp +++ b/jsk_pcl_ros/src/primitive_shape_classifier_nodelet.cpp @@ -57,7 +57,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PrimitiveShapeClassifier::configCallback, this, _1, _2); + boost::bind(&PrimitiveShapeClassifier::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_class_ = advertise(*pnh_, "output", 1); @@ -89,7 +89,7 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_cloud_, sub_normal_, sub_indices_, sub_polygons_); - sync_->registerCallback(boost::bind(&PrimitiveShapeClassifier::process, this, _1, _2, _3, _4)); + sync_->registerCallback(boost::bind(&PrimitiveShapeClassifier::process, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } void PrimitiveShapeClassifier::unsubscribe() diff --git a/jsk_pcl_ros/src/rearrange_bounding_box_nodelet.cpp b/jsk_pcl_ros/src/rearrange_bounding_box_nodelet.cpp index 488b87df75..f0c30df8e1 100644 --- a/jsk_pcl_ros/src/rearrange_bounding_box_nodelet.cpp +++ b/jsk_pcl_ros/src/rearrange_bounding_box_nodelet.cpp @@ -53,7 +53,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&RearrangeBoundingBox::configCallback, this, _1, _2); + boost::bind(&RearrangeBoundingBox::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_bouding_box_array_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp b/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp index 04e9fd094f..08c4fb6ef8 100644 --- a/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp @@ -51,7 +51,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &RegionGrowingMultiplePlaneSegmentation::configCallback, this, _1, _2); + &RegionGrowingMultiplePlaneSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_polygons_ = advertise( @@ -91,7 +91,7 @@ namespace jsk_pcl_ros sync_->connectInput(sub_input_, sub_normal_); sync_->registerCallback( boost::bind(&RegionGrowingMultiplePlaneSegmentation::segment, this, - _1, _2)); + boost::placeholders::_1, boost::placeholders::_2)); } void RegionGrowingMultiplePlaneSegmentation::unsubscribe() diff --git a/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp b/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp index b8a9b5d64f..8fdb9724d9 100644 --- a/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros ConnectionBasedNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&RegionGrowingSegmentation::configCallback, this, _1, _2); + boost::bind (&RegionGrowingSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp b/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp index 5181041b59..72032922cf 100644 --- a/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp +++ b/jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &ResizePointsPublisher::configCallback, this, _1, _2); + &ResizePointsPublisher::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); resizedmask_sub_ = pnh_->subscribe("input/mask", 1, &ResizePointsPublisher::resizedmaskCallback, this); @@ -95,10 +95,10 @@ namespace jsk_pcl_ros sync_ = boost::make_shared >(10); sync_->connectInput(sub_input_, sub_indices_); if (!not_use_rgb_) { - sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter, this, _1, _2)); + sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter, this, boost::placeholders::_1, boost::placeholders::_2)); } else { - sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter, this, _1, _2)); + sync_->registerCallback(boost::bind(&ResizePointsPublisher::filter, this, boost::placeholders::_1, boost::placeholders::_2)); } } else { diff --git a/jsk_pcl_ros/src/roi_clipper_nodelet.cpp b/jsk_pcl_ros/src/roi_clipper_nodelet.cpp index ef21861081..a75f7d621d 100644 --- a/jsk_pcl_ros/src/roi_clipper_nodelet.cpp +++ b/jsk_pcl_ros/src/roi_clipper_nodelet.cpp @@ -76,7 +76,7 @@ namespace jsk_pcl_ros sub_info_.subscribe(*pnh_, "input/camera_info", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_image_, sub_info_); - sync_->registerCallback(boost::bind(&ROIClipper::clip, this, _1, _2)); + sync_->registerCallback(boost::bind(&ROIClipper::clip, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_image_no_sync_ = pnh_->subscribe( diff --git a/jsk_pcl_ros/src/selected_cluster_publisher_nodelet.cpp b/jsk_pcl_ros/src/selected_cluster_publisher_nodelet.cpp index 6f649eb04a..4b9bd9c75e 100644 --- a/jsk_pcl_ros/src/selected_cluster_publisher_nodelet.cpp +++ b/jsk_pcl_ros/src/selected_cluster_publisher_nodelet.cpp @@ -66,7 +66,7 @@ namespace jsk_pcl_ros sub_indices_.subscribe(*pnh_, "indices", 1); sub_index_.subscribe(*pnh_, "selected_index", 1); sync_->connectInput(sub_input_, sub_indices_, sub_index_); - sync_->registerCallback(boost::bind(&SelectedClusterPublisher::extract, this, _1, _2, _3)); + sync_->registerCallback(boost::bind(&SelectedClusterPublisher::extract, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void SelectedClusterPublisher::unsubscribe() diff --git a/jsk_pcl_ros/src/snapit_nodelet.cpp b/jsk_pcl_ros/src/snapit_nodelet.cpp index eca339429a..ef6379f900 100644 --- a/jsk_pcl_ros/src/snapit_nodelet.cpp +++ b/jsk_pcl_ros/src/snapit_nodelet.cpp @@ -94,7 +94,7 @@ namespace jsk_pcl_ros = boost::make_shared >(100); sync_polygon_->connectInput(sub_polygons_, sub_coefficients_); sync_polygon_->registerCallback( - boost::bind(&SnapIt::polygonCallback, this, _1, _2)); + boost::bind(&SnapIt::polygonCallback, this, boost::placeholders::_1, boost::placeholders::_2)); polygon_align_sub_ = pnh_->subscribe("input/plane_align", 1, &SnapIt::polygonAlignCallback, this); convex_align_sub_ = pnh_->subscribe("input/convex_align", 1, diff --git a/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp b/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp index c72b8d4a9f..e340e17ea8 100644 --- a/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp +++ b/jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &SupervoxelSegmentation::configCallback, this, _1, _2); + &SupervoxelSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_indices_ = advertise( *pnh_, "output/indices", 1); diff --git a/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp b/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp index 288862d870..10fc63f648 100644 --- a/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp +++ b/jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp @@ -41,7 +41,7 @@ namespace jsk_pcl_ros srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&TargetAdaptiveTracking::configCallback, this, _1, _2); + boost::bind(&TargetAdaptiveTracking::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); this->pub_cloud_ = advertise( @@ -92,7 +92,7 @@ namespace jsk_pcl_ros sub_obj_cloud_, sub_bkgd_cloud_, sub_obj_pose_); this->obj_sync_->registerCallback( boost::bind(&TargetAdaptiveTracking::objInitCallback, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); this->sub_cloud_.subscribe(*pnh_, "input_cloud", 1); this->sub_pose_.subscribe(*pnh_, "input_pose", 1); this->sync_ = boost::make_sharedsync_->connectInput(sub_cloud_, sub_pose_); this->sync_->registerCallback( boost::bind(&TargetAdaptiveTracking::callback, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void TargetAdaptiveTracking::unsubscribe() diff --git a/jsk_pcl_ros/src/torus_finder_nodelet.cpp b/jsk_pcl_ros/src/torus_finder_nodelet.cpp index 80d521e928..de294f2273 100644 --- a/jsk_pcl_ros/src/torus_finder_nodelet.cpp +++ b/jsk_pcl_ros/src/torus_finder_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros pnh_->param("use_normal", use_normal_, false); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&TorusFinder::configCallback, this, _1, _2); + boost::bind (&TorusFinder::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_torus_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/uniform_sampling_nodelet.cpp b/jsk_pcl_ros/src/uniform_sampling_nodelet.cpp index 99b85350da..e1523b57f3 100644 --- a/jsk_pcl_ros/src/uniform_sampling_nodelet.cpp +++ b/jsk_pcl_ros/src/uniform_sampling_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&UniformSampling::configCallback, this, _1, _2); + boost::bind (&UniformSampling::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros/src/voxel_grid_large_scale_nodelet.cpp b/jsk_pcl_ros/src/voxel_grid_large_scale_nodelet.cpp index c0c1c7d7e5..f5f7ff8784 100644 --- a/jsk_pcl_ros/src/voxel_grid_large_scale_nodelet.cpp +++ b/jsk_pcl_ros/src/voxel_grid_large_scale_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind(&VoxelGridLargeScale::configCallback, this, _1, _2); + boost::bind(&VoxelGridLargeScale::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros_utils/src/add_point_indices_nodelet.cpp b/jsk_pcl_ros_utils/src/add_point_indices_nodelet.cpp index bf92733ba5..52ed901ac2 100644 --- a/jsk_pcl_ros_utils/src/add_point_indices_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/add_point_indices_nodelet.cpp @@ -68,14 +68,14 @@ namespace jsk_pcl_ros_utils async_->connectInput(sub_src1_, sub_src2_); async_->registerCallback( boost::bind(&AddPointIndices::add, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_src1_, sub_src2_); sync_->registerCallback( boost::bind(&AddPointIndices::add, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/bounding_box_array_to_bounding_box_nodelet.cpp b/jsk_pcl_ros_utils/src/bounding_box_array_to_bounding_box_nodelet.cpp index 18e508b45e..8a93f4a9b0 100644 --- a/jsk_pcl_ros_utils/src/bounding_box_array_to_bounding_box_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/bounding_box_array_to_bounding_box_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros_utils // dynamic_reconfigure srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&BoundingBoxArrayToBoundingBox::configCallback, this, _1, _2); + boost::bind(&BoundingBoxArrayToBoundingBox::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/cloud_on_plane_nodelet.cpp b/jsk_pcl_ros_utils/src/cloud_on_plane_nodelet.cpp index 669afbab3e..66a2c0841e 100644 --- a/jsk_pcl_ros_utils/src/cloud_on_plane_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/cloud_on_plane_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &CloudOnPlane::configCallback, this, _1, _2); + &CloudOnPlane::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); @@ -75,11 +75,11 @@ namespace jsk_pcl_ros_utils if (approximate_sync_) { async_ = boost::make_shared > (100); async_->connectInput(sub_cloud_, sub_polygon_); - async_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2)); + async_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared > (100); sync_->connectInput(sub_cloud_, sub_polygon_); - sync_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, _1, _2)); + sync_->registerCallback(boost::bind(&CloudOnPlane::predicate, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/cluster_point_indices_label_filter_nodelet.cpp b/jsk_pcl_ros_utils/src/cluster_point_indices_label_filter_nodelet.cpp index fa231106b5..f12bdc9e6d 100644 --- a/jsk_pcl_ros_utils/src/cluster_point_indices_label_filter_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/cluster_point_indices_label_filter_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros_utils // dynamic_reconfigure srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ClusterPointIndicesLabelFilter::configCallback, this, _1, _2); + boost::bind (&ClusterPointIndicesLabelFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); @@ -68,13 +68,13 @@ namespace jsk_pcl_ros_utils async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_indices_, sub_labels_); async_->registerCallback(boost::bind(&ClusterPointIndicesLabelFilter::filter, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_indices_, sub_labels_); sync_->registerCallback(boost::bind(&ClusterPointIndicesLabelFilter::filter, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/cluster_point_indices_to_point_indices_nodelet.cpp b/jsk_pcl_ros_utils/src/cluster_point_indices_to_point_indices_nodelet.cpp index b43f8d072a..1af1cfd3c2 100644 --- a/jsk_pcl_ros_utils/src/cluster_point_indices_to_point_indices_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/cluster_point_indices_to_point_indices_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros_utils // dynamic_reconfigure srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&ClusterPointIndicesToPointIndices::configCallback, this, _1, _2); + boost::bind(&ClusterPointIndicesToPointIndices::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/colorize_distance_from_plane_nodelet.cpp b/jsk_pcl_ros_utils/src/colorize_distance_from_plane_nodelet.cpp index dff685289b..7c2b3eff10 100644 --- a/jsk_pcl_ros_utils/src/colorize_distance_from_plane_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/colorize_distance_from_plane_nodelet.cpp @@ -53,7 +53,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ColorizeDistanceFromPlane::configCallback, this, _1, _2); + boost::bind (&ColorizeDistanceFromPlane::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); onInitPostProcess(); } @@ -82,7 +82,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_input_, sub_coefficients_, sub_polygons_); sync_->registerCallback(boost::bind( &ColorizeDistanceFromPlane::colorize, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void ColorizeDistanceFromPlane::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/delay_pointcloud_nodelet.cpp b/jsk_pcl_ros_utils/src/delay_pointcloud_nodelet.cpp index f4cf8b40d0..aec342a9c7 100644 --- a/jsk_pcl_ros_utils/src/delay_pointcloud_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/delay_pointcloud_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&DelayPointCloud::configCallback, this, _1, _2); + boost::bind (&DelayPointCloud::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("delay_time", delay_time_, 0.1); @@ -73,7 +73,7 @@ namespace jsk_pcl_ros_utils sub_.subscribe(*pnh_, "input", 1); time_sequencer_ = boost::make_shared >(ros::Duration(delay_time_), ros::Duration(0.01), queue_size_); time_sequencer_->connectInput(sub_); - time_sequencer_->registerCallback(boost::bind(&DelayPointCloud::delay, this, _1)); + time_sequencer_->registerCallback(boost::bind(&DelayPointCloud::delay, this, boost::placeholders::_1)); } void DelayPointCloud::unsubscribe() { diff --git a/jsk_pcl_ros_utils/src/depth_image_error_nodelet.cpp b/jsk_pcl_ros_utils/src/depth_image_error_nodelet.cpp index 8dc2b4d962..3ac8393f0b 100644 --- a/jsk_pcl_ros_utils/src/depth_image_error_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/depth_image_error_nodelet.cpp @@ -69,13 +69,13 @@ namespace jsk_pcl_ros_utils async_ = boost::make_shared >(1000); async_->connectInput(sub_image_, sub_point_, sub_camera_info_); async_->registerCallback(boost::bind(&DepthImageError::calcError, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_ = boost::make_shared >(1000); sync_->connectInput(sub_image_, sub_point_, sub_camera_info_); sync_->registerCallback(boost::bind(&DepthImageError::calcError, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } } diff --git a/jsk_pcl_ros_utils/src/mask_image_to_depth_considered_mask_image_nodelet.cpp b/jsk_pcl_ros_utils/src/mask_image_to_depth_considered_mask_image_nodelet.cpp index ad21fe1713..662aedc6de 100644 --- a/jsk_pcl_ros_utils/src/mask_image_to_depth_considered_mask_image_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/mask_image_to_depth_considered_mask_image_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &MaskImageToDepthConsideredMaskImage::configCallback, this, _1, _2); + &MaskImageToDepthConsideredMaskImage::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); sub_ = pnh_->subscribe("input/maskregion", 1, &MaskImageToDepthConsideredMaskImage::mask_region_callback, this); region_width_ = 0; @@ -133,13 +133,13 @@ namespace jsk_pcl_ros_utils if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_input_, sub_image_); - async_->registerCallback(boost::bind(&MaskImageToDepthConsideredMaskImage::extractmask, this, _1, _2)); + async_->registerCallback(boost::bind(&MaskImageToDepthConsideredMaskImage::extractmask, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_input_, sub_image_); sync_->registerCallback(boost::bind(&MaskImageToDepthConsideredMaskImage::extractmask, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/normal_concatenater_nodelet.cpp b/jsk_pcl_ros_utils/src/normal_concatenater_nodelet.cpp index 8b1f76e91d..2b54a6d9c6 100644 --- a/jsk_pcl_ros_utils/src/normal_concatenater_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/normal_concatenater_nodelet.cpp @@ -107,12 +107,12 @@ namespace jsk_pcl_ros_utils if (use_async_) { async_ = boost::make_shared >(maximum_queue_size_); async_->connectInput(sub_xyz_, sub_normal_); - async_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2)); + async_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(maximum_queue_size_); sync_->connectInput(sub_xyz_, sub_normal_); - sync_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, _1, _2)); + sync_->registerCallback(boost::bind(&NormalConcatenater::concatenate, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/planar_pointcloud_simulator_nodelet.cpp b/jsk_pcl_ros_utils/src/planar_pointcloud_simulator_nodelet.cpp index fa6862f1c1..88a58410ff 100644 --- a/jsk_pcl_ros_utils/src/planar_pointcloud_simulator_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/planar_pointcloud_simulator_nodelet.cpp @@ -75,7 +75,7 @@ namespace jsk_pcl_ros_utils DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PlanarPointCloudSimulatorNodelet::configCallback, this, _1, _2); + boost::bind (&PlanarPointCloudSimulatorNodelet::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise( diff --git a/jsk_pcl_ros_utils/src/plane_concatenator_nodelet.cpp b/jsk_pcl_ros_utils/src/plane_concatenator_nodelet.cpp index 6aff616636..e1623a4919 100644 --- a/jsk_pcl_ros_utils/src/plane_concatenator_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/plane_concatenator_nodelet.cpp @@ -50,7 +50,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &PlaneConcatenator::configCallback, this, _1, _2); + &PlaneConcatenator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_indices_ = advertise( @@ -84,7 +84,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_cloud_, sub_indices_, sub_polygon_, sub_coefficients_); sync_->registerCallback(boost::bind(&PlaneConcatenator::concatenate, this, - _1, _2, _3, _4)); + boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } void PlaneConcatenator::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/plane_reasoner_nodelet.cpp b/jsk_pcl_ros_utils/src/plane_reasoner_nodelet.cpp index 89567d1b4b..c4175bb112 100644 --- a/jsk_pcl_ros_utils/src/plane_reasoner_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/plane_reasoner_nodelet.cpp @@ -53,7 +53,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &PlaneReasoner::configCallback, this, _1, _2); + &PlaneReasoner::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //////////////////////////////////////////////////////// @@ -99,7 +99,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_input_, sub_inliers_, sub_coefficients_, sub_polygons_); sync_->registerCallback(boost::bind(&PlaneReasoner::reason, - this, _1, _2, _3, _4)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); } void PlaneReasoner::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/plane_rejector_nodelet.cpp b/jsk_pcl_ros_utils/src/plane_rejector_nodelet.cpp index 8a1e534d0e..1bfff10bfc 100644 --- a/jsk_pcl_ros_utils/src/plane_rejector_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/plane_rejector_nodelet.cpp @@ -57,7 +57,7 @@ namespace jsk_pcl_ros_utils getName() + "::PlaneRejector", boost::bind( &PlaneRejector::updateDiagnosticsPlaneRejector, - this, _1)); + this, boost::placeholders::_1)); if (!pnh_->getParam("processing_frame_id", processing_frame_id_)) { NODELET_FATAL("You need to specify ~processing_frame_id"); return; @@ -82,7 +82,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PlaneRejector::configCallback, this, _1, _2); + boost::bind (&PlaneRejector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); polygons_pub_ = advertise( @@ -98,7 +98,7 @@ namespace jsk_pcl_ros_utils ros::Duration(1.0), boost::bind(&PlaneRejector::updateDiagnostics, this, - _1)); + boost::placeholders::_1)); onInitPostProcess(); } @@ -122,14 +122,14 @@ namespace jsk_pcl_ros_utils sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1); sub_inliers_.subscribe(*pnh_, "input_inliers", 1); sync_inlier_->connectInput(sub_polygons_, sub_coefficients_, sub_inliers_); - sync_inlier_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2, _3)); + sync_inlier_->registerCallback(boost::bind(&PlaneRejector::reject, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_ = boost::make_shared >(100); sub_polygons_.subscribe(*pnh_, "input_polygons", 1); sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1); sync_->connectInput(sub_polygons_, sub_coefficients_); - sync_->registerCallback(boost::bind(&PlaneRejector::reject, this, _1, _2)); + sync_->registerCallback(boost::bind(&PlaneRejector::reject, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/point_indices_to_mask_image_nodelet.cpp b/jsk_pcl_ros_utils/src/point_indices_to_mask_image_nodelet.cpp index ccdbb6a8c7..558e6a0278 100644 --- a/jsk_pcl_ros_utils/src/point_indices_to_mask_image_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/point_indices_to_mask_image_nodelet.cpp @@ -75,13 +75,13 @@ namespace jsk_pcl_ros_utils if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_input_, sub_image_); - async_->registerCallback(boost::bind(&PointIndicesToMaskImage::mask, this, _1, _2)); + async_->registerCallback(boost::bind(&PointIndicesToMaskImage::mask, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_input_, sub_image_); sync_->registerCallback(boost::bind(&PointIndicesToMaskImage::mask, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } } diff --git a/jsk_pcl_ros_utils/src/pointcloud_relative_from_pose_stamped_nodelet.cpp b/jsk_pcl_ros_utils/src/pointcloud_relative_from_pose_stamped_nodelet.cpp index 6779436365..6e764e5456 100644 --- a/jsk_pcl_ros_utils/src/pointcloud_relative_from_pose_stamped_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pointcloud_relative_from_pose_stamped_nodelet.cpp @@ -70,11 +70,11 @@ namespace jsk_pcl_ros_utils if (approximate_sync_) { async_ = boost::make_shared >(100); async_->connectInput(sub_cloud_, sub_pose_); - async_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, _1, _2)); + async_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_cloud_, sub_pose_); - sync_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, _1, _2)); + sync_->registerCallback(boost::bind(&PointCloudRelativeFromPoseStamped::transform, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/pointcloud_to_mask_image_nodelet.cpp b/jsk_pcl_ros_utils/src/pointcloud_to_mask_image_nodelet.cpp index acf443d8d2..dc8fdd1530 100644 --- a/jsk_pcl_ros_utils/src/pointcloud_to_mask_image_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pointcloud_to_mask_image_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared >(*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PointCloudToMaskImage::configCallback, this, _1, _2); + boost::bind(&PointCloudToMaskImage::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp index e4219078bb..292edea305 100644 --- a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp @@ -114,7 +114,7 @@ namespace jsk_pcl_ros_utils { PCLNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); - dynamic_reconfigure::Server::CallbackType f = boost::bind(&PointCloudToPCD::configCallback, this, _1, _2); + dynamic_reconfigure::Server::CallbackType f = boost::bind(&PointCloudToPCD::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); srv_save_pcd_server_ = pnh_->advertiseService("save_pcd", &PointCloudToPCD::savePCDCallback, this); tf_listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance(); @@ -145,7 +145,7 @@ namespace jsk_pcl_ros_utils duration_ = config.duration; timer_.stop(); if (duration_ != 0) { - timer_ = pnh_->createTimer(ros::Duration(duration_), boost::bind(&PointCloudToPCD::timerCallback, this, _1)); + timer_ = pnh_->createTimer(ros::Duration(duration_), boost::bind(&PointCloudToPCD::timerCallback, this, boost::placeholders::_1)); } } } diff --git a/jsk_pcl_ros_utils/src/polygon_appender_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_appender_nodelet.cpp index 611f408137..5d6940d6dd 100644 --- a/jsk_pcl_ros_utils/src/polygon_appender_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_appender_nodelet.cpp @@ -48,7 +48,7 @@ namespace jsk_pcl_ros_utils sync_ = boost::make_shared >(100); sync_->connectInput(sub_polygon0_, sub_coefficients0_, sub_polygon1_, sub_coefficients1_); - sync_->registerCallback(boost::bind(&PolygonAppender::callback2, this, _1, _2, _3, _4)); + sync_->registerCallback(boost::bind(&PolygonAppender::callback2, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4)); onInitPostProcess(); } diff --git a/jsk_pcl_ros_utils/src/polygon_array_angle_likelihood_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_angle_likelihood_nodelet.cpp index b82ae30b81..d33b85b456 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_angle_likelihood_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_angle_likelihood_nodelet.cpp @@ -74,7 +74,7 @@ namespace jsk_pcl_ros_utils target_frame_id_, tf_queue_size_)); tf_filter_->registerCallback( - boost::bind(&PolygonArrayAngleLikelihood::likelihood, this, _1)); + boost::bind(&PolygonArrayAngleLikelihood::likelihood, this, boost::placeholders::_1)); } void PolygonArrayAngleLikelihood::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_array_area_likelihood_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_area_likelihood_nodelet.cpp index 2dd15ba466..9ecea11433 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_area_likelihood_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_area_likelihood_nodelet.cpp @@ -47,7 +47,7 @@ namespace jsk_pcl_ros_utils DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PolygonArrayAreaLikelihood::configCallback, this, _1, _2); + boost::bind (&PolygonArrayAreaLikelihood::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); diff --git a/jsk_pcl_ros_utils/src/polygon_array_distance_likelihood_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_distance_likelihood_nodelet.cpp index 0b0a3c6deb..0dc9025005 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_distance_likelihood_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_distance_likelihood_nodelet.cpp @@ -65,7 +65,7 @@ namespace jsk_pcl_ros_utils target_frame_id_, tf_queue_size_)); tf_filter_->registerCallback( - boost::bind(&PolygonArrayDistanceLikelihood::likelihood, this, _1)); + boost::bind(&PolygonArrayDistanceLikelihood::likelihood, this, boost::placeholders::_1)); } void PolygonArrayDistanceLikelihood::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_array_foot_angle_likelihood_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_foot_angle_likelihood_nodelet.cpp index 7bc078885e..086ff9a3c0 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_foot_angle_likelihood_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_foot_angle_likelihood_nodelet.cpp @@ -75,7 +75,7 @@ namespace jsk_pcl_ros_utils target_frame_id_, tf_queue_size_)); tf_filter_->registerCallback( - boost::bind(&PolygonArrayFootAngleLikelihood::likelihood, this, _1)); + boost::bind(&PolygonArrayFootAngleLikelihood::likelihood, this, boost::placeholders::_1)); } void PolygonArrayFootAngleLikelihood::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp index db521119fd..5072b5efc8 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_likelihood_filter_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros_utils srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PolygonArrayLikelihoodFilter::configCallback, this, _1, _2); + boost::bind(&PolygonArrayLikelihoodFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_polygons_ = advertise( @@ -79,7 +79,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_polygons_, sub_coefficients_); sync_->registerCallback(boost::bind( &PolygonArrayLikelihoodFilter::filter, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_polygons_alone_ = pnh_->subscribe( "input_polygons", 1, &PolygonArrayLikelihoodFilter::filter, this); diff --git a/jsk_pcl_ros_utils/src/polygon_array_transformer_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_transformer_nodelet.cpp index 07fd7721d6..499accda0e 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_transformer_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_transformer_nodelet.cpp @@ -72,7 +72,7 @@ namespace jsk_pcl_ros_utils sub_polygons_.subscribe(*pnh_, "input_polygons", 1); sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1); sync_->connectInput(sub_polygons_, sub_coefficients_); - sync_->registerCallback(boost::bind(&PolygonArrayTransformer::transform, this, _1, _2)); + sync_->registerCallback(boost::bind(&PolygonArrayTransformer::transform, this, boost::placeholders::_1, boost::placeholders::_2)); } void PolygonArrayTransformer::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_array_unwrapper_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_unwrapper_nodelet.cpp index 2a26e4afd9..1e9b492a95 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_unwrapper_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_unwrapper_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_pcl_ros_utils "output_coefficients", 1); srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&PolygonArrayUnwrapper::configCallback, this, _1, _2); + boost::bind(&PolygonArrayUnwrapper::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); onInitPostProcess(); } @@ -73,7 +73,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_polygon_, sub_coefficients_); sync_->registerCallback(boost::bind( &PolygonArrayUnwrapper::unwrap, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void PolygonArrayUnwrapper::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_array_wrapper_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_array_wrapper_nodelet.cpp index 6331f99ec2..c0d304c7f6 100644 --- a/jsk_pcl_ros_utils/src/polygon_array_wrapper_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_array_wrapper_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_polygon_, sub_coefficients_); sync_->registerCallback(boost::bind( &PolygonArrayWrapper::wrap, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } void PolygonArrayWrapper::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_flipper_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_flipper_nodelet.cpp index 46fbf1e053..28b618026d 100644 --- a/jsk_pcl_ros_utils/src/polygon_flipper_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_flipper_nodelet.cpp @@ -84,10 +84,10 @@ namespace jsk_pcl_ros_utils sub_indices_.subscribe(*pnh_, "input/indices", 1); sync_->connectInput(sub_polygons_, sub_indices_, sub_coefficients_); } else { - sub_polygons_.registerCallback(boost::bind(&PolygonFlipper::fillEmptyIndices, this, _1)); + sub_polygons_.registerCallback(boost::bind(&PolygonFlipper::fillEmptyIndices, this, boost::placeholders::_1)); sync_->connectInput(sub_polygons_, sub_indices_null_, sub_coefficients_); } - sync_->registerCallback(boost::bind(&PolygonFlipper::flip, this, _1, _2, _3)); + sync_->registerCallback(boost::bind(&PolygonFlipper::flip, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void PolygonFlipper::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/polygon_magnifier_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_magnifier_nodelet.cpp index 7f2f26cb4c..161c4667c4 100644 --- a/jsk_pcl_ros_utils/src/polygon_magnifier_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_magnifier_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros_utils DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PolygonMagnifier::configCallback, this, _1, _2); + boost::bind (&PolygonMagnifier::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/polygon_points_sampler_nodelet.cpp b/jsk_pcl_ros_utils/src/polygon_points_sampler_nodelet.cpp index 5f4d2b85d2..d65f47442a 100644 --- a/jsk_pcl_ros_utils/src/polygon_points_sampler_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/polygon_points_sampler_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros_utils DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PolygonPointsSampler::configCallback, this, _1, _2); + boost::bind (&PolygonPointsSampler::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); @@ -70,7 +70,7 @@ namespace jsk_pcl_ros_utils sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1); sync_ = boost::make_shared >(100); sync_->connectInput(sub_polygons_, sub_coefficients_); - sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, _1, _2)); + sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, boost::placeholders::_1, boost::placeholders::_2)); } void PolygonPointsSampler::unsubscribe() diff --git a/jsk_pcl_ros_utils/src/pose_with_covariance_stamped_to_gaussian_pointcloud_nodelet.cpp b/jsk_pcl_ros_utils/src/pose_with_covariance_stamped_to_gaussian_pointcloud_nodelet.cpp index 5068ce2c72..8f740946bf 100644 --- a/jsk_pcl_ros_utils/src/pose_with_covariance_stamped_to_gaussian_pointcloud_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pose_with_covariance_stamped_to_gaussian_pointcloud_nodelet.cpp @@ -46,7 +46,7 @@ namespace jsk_pcl_ros_utils DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&PoseWithCovarianceStampedToGaussianPointCloud::configCallback, this, _1, _2); + boost::bind (&PoseWithCovarianceStampedToGaussianPointCloud::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/spherical_pointcloud_simulator_nodelet.cpp b/jsk_pcl_ros_utils/src/spherical_pointcloud_simulator_nodelet.cpp index 970d473685..bde8b90f84 100644 --- a/jsk_pcl_ros_utils/src/spherical_pointcloud_simulator_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/spherical_pointcloud_simulator_nodelet.cpp @@ -44,7 +44,7 @@ namespace jsk_pcl_ros_utils rotate_velocity_ = 0.5; srv_ = boost::make_shared > (*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind (&SphericalPointCloudSimulator::configCallback, this, _1, _2); + boost::bind (&SphericalPointCloudSimulator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); double rate; @@ -53,7 +53,7 @@ namespace jsk_pcl_ros_utils ros::Duration(1 / rate), boost::bind( &SphericalPointCloudSimulator::timerCallback, this, - _1)); + boost::placeholders::_1)); } pub_ = advertise( *pnh_, "output", 1); diff --git a/jsk_pcl_ros_utils/src/static_polygon_array_publisher_nodelet.cpp b/jsk_pcl_ros_utils/src/static_polygon_array_publisher_nodelet.cpp index 4f0fbcf56c..494b5d634f 100644 --- a/jsk_pcl_ros_utils/src/static_polygon_array_publisher_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/static_polygon_array_publisher_nodelet.cpp @@ -121,7 +121,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_input_, sub_trigger_); sync_->registerCallback(boost::bind( &StaticPolygonArrayPublisher::triggerCallback, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/subtract_point_indices_nodelet.cpp b/jsk_pcl_ros_utils/src/subtract_point_indices_nodelet.cpp index f24e6ed205..4cc6540dfd 100644 --- a/jsk_pcl_ros_utils/src/subtract_point_indices_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/subtract_point_indices_nodelet.cpp @@ -68,14 +68,14 @@ namespace jsk_pcl_ros_utils async_->connectInput(sub_src1_, sub_src2_); async_->registerCallback( boost::bind(&SubtractPointIndices::subtract, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_src1_, sub_src2_); sync_->registerCallback( boost::bind(&SubtractPointIndices::subtract, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_pcl_ros_utils/src/tf_transform_bounding_box_array_nodelet.cpp b/jsk_pcl_ros_utils/src/tf_transform_bounding_box_array_nodelet.cpp index fd3c72ea8c..7ecebadb7c 100644 --- a/jsk_pcl_ros_utils/src/tf_transform_bounding_box_array_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/tf_transform_bounding_box_array_nodelet.cpp @@ -68,7 +68,7 @@ namespace jsk_pcl_ros_utils *tf_listener_, target_frame_id_, tf_queue_size_)); - tf_filter_->registerCallback(boost::bind(&TfTransformBoundingBoxArray::transform, this, _1)); + tf_filter_->registerCallback(boost::bind(&TfTransformBoundingBoxArray::transform, this, boost::placeholders::_1)); } } diff --git a/jsk_pcl_ros_utils/src/tf_transform_bounding_box_nodelet.cpp b/jsk_pcl_ros_utils/src/tf_transform_bounding_box_nodelet.cpp index 358e10580a..8ff7359d59 100644 --- a/jsk_pcl_ros_utils/src/tf_transform_bounding_box_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/tf_transform_bounding_box_nodelet.cpp @@ -67,7 +67,7 @@ namespace jsk_pcl_ros_utils *tf_listener_, target_frame_id_, tf_queue_size_)); - tf_filter_->registerCallback(boost::bind(&TfTransformBoundingBox::transform, this, _1)); + tf_filter_->registerCallback(boost::bind(&TfTransformBoundingBox::transform, this, boost::placeholders::_1)); } } diff --git a/jsk_pcl_ros_utils/src/tf_transform_cloud_nodelet.cpp b/jsk_pcl_ros_utils/src/tf_transform_cloud_nodelet.cpp index 2d0771eb2c..edc4a4b5e5 100644 --- a/jsk_pcl_ros_utils/src/tf_transform_cloud_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/tf_transform_cloud_nodelet.cpp @@ -105,7 +105,7 @@ namespace jsk_pcl_ros_utils *tf_listener_, target_frame_id_, tf_queue_size_)); - tf_filter_->registerCallback(boost::bind(&TfTransformCloud::transform, this, _1)); + tf_filter_->registerCallback(boost::bind(&TfTransformCloud::transform, this, boost::placeholders::_1)); } } diff --git a/jsk_pcl_ros_utils/src/transform_pointcloud_in_bounding_box_nodelet.cpp b/jsk_pcl_ros_utils/src/transform_pointcloud_in_bounding_box_nodelet.cpp index e38d4715f6..3b63c299e6 100644 --- a/jsk_pcl_ros_utils/src/transform_pointcloud_in_bounding_box_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/transform_pointcloud_in_bounding_box_nodelet.cpp @@ -61,7 +61,7 @@ namespace jsk_pcl_ros_utils sync_->connectInput(sub_input_, sub_box_); sync_->registerCallback(boost::bind( &TransformPointcloudInBoundingBox::transform, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } TransformPointcloudInBoundingBox::~TransformPointcloudInBoundingBox() { diff --git a/jsk_perception/src/add_mask_image.cpp b/jsk_perception/src/add_mask_image.cpp index 0aff3a317d..5a2df2328f 100644 --- a/jsk_perception/src/add_mask_image.cpp +++ b/jsk_perception/src/add_mask_image.cpp @@ -70,12 +70,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(100); async_->connectInput(sub_src1_, sub_src2_); - async_->registerCallback(boost::bind(&AddMaskImage::add, this, _1, _2)); + async_->registerCallback(boost::bind(&AddMaskImage::add, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_src1_, sub_src2_); - sync_->registerCallback(boost::bind(&AddMaskImage::add, this, _1, _2)); + sync_->registerCallback(boost::bind(&AddMaskImage::add, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input/src1")("~input/src2"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/apply_mask_image.cpp b/jsk_perception/src/apply_mask_image.cpp index 5a70e523f8..cb5c04baa0 100644 --- a/jsk_perception/src/apply_mask_image.cpp +++ b/jsk_perception/src/apply_mask_image.cpp @@ -85,12 +85,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_), (max_interval_duration_); async_->connectInput(sub_image_, sub_mask_); - async_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2)); + async_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_image_, sub_mask_); - sync_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2)); + sync_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input")("~input/mask"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/background_substraction_nodelet.cpp b/jsk_perception/src/background_substraction_nodelet.cpp index d35bd607e3..3fc21827f4 100644 --- a/jsk_perception/src/background_substraction_nodelet.cpp +++ b/jsk_perception/src/background_substraction_nodelet.cpp @@ -46,7 +46,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &BackgroundSubstraction::configCallback, this, _1, _2); + &BackgroundSubstraction::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); image_pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/blob_detector.cpp b/jsk_perception/src/blob_detector.cpp index 41454144d0..445770fdcf 100644 --- a/jsk_perception/src/blob_detector.cpp +++ b/jsk_perception/src/blob_detector.cpp @@ -49,7 +49,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &BlobDetector::configCallback, this, _1, _2); + &BlobDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise( diff --git a/jsk_perception/src/bounding_box_to_rect.cpp b/jsk_perception/src/bounding_box_to_rect.cpp index 507e88fd82..8390e1e5d4 100644 --- a/jsk_perception/src/bounding_box_to_rect.cpp +++ b/jsk_perception/src/bounding_box_to_rect.cpp @@ -76,22 +76,22 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_info_, sub_boxes_); - async_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2)); + async_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_info_, sub_boxes_); - sync_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, _1, _2)); + sync_->registerCallback(boost::bind(&BoundingBoxToRect::inputCallback, this, boost::placeholders::_1, boost::placeholders::_2)); } // camera_info + bounding box sub_box_.subscribe(*pnh_, "input/box", 1); if (approximate_sync_) { async_box_ = boost::make_shared >(queue_size_); async_box_->connectInput(sub_info_, sub_box_); - async_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2)); + async_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_box_ = boost::make_shared >(queue_size_); sync_box_->connectInput(sub_info_, sub_box_); - sync_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, _1, _2)); + sync_box_->registerCallback(boost::bind(&BoundingBoxToRect::inputBoxCallback, this, boost::placeholders::_1, boost::placeholders::_2)); } } @@ -125,7 +125,7 @@ namespace jsk_perception *tf_listener_, frame_id_, tf_queue_size_)); - tf_filter_->registerCallback(boost::bind(&BoundingBoxToRect::internalCallback, this, _1)); + tf_filter_->registerCallback(boost::bind(&BoundingBoxToRect::internalCallback, this, boost::placeholders::_1)); } jsk_recognition_msgs::BoundingBoxArrayWithCameraInfo internal_msg; internal_msg.header = boxes_msg->header; diff --git a/jsk_perception/src/camshiftdemo.cpp b/jsk_perception/src/camshiftdemo.cpp index e63814c0f9..49d7e0554c 100644 --- a/jsk_perception/src/camshiftdemo.cpp +++ b/jsk_perception/src/camshiftdemo.cpp @@ -115,7 +115,7 @@ class CamShiftDemo config_.vmin = vmin_; config_.vmax = vmax_; config_.smin = smin_; - ReconfigureServer::CallbackType f = boost::bind(&CamShiftDemo::configCb, this, _1, _2); + ReconfigureServer::CallbackType f = boost::bind(&CamShiftDemo::configCb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_.setCallback(f); diff --git a/jsk_perception/src/color_histogram.cpp b/jsk_perception/src/color_histogram.cpp index caa31318f2..07da4517f9 100644 --- a/jsk_perception/src/color_histogram.cpp +++ b/jsk_perception/src/color_histogram.cpp @@ -86,7 +86,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ColorHistogram::configCallback, this, _1, _2); + boost::bind (&ColorHistogram::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); } @@ -102,7 +102,7 @@ namespace jsk_perception = boost::make_shared >(10); sync_->connectInput(image_sub_, rectangle_sub_); sync_->registerCallback(boost::bind( - &ColorHistogram::extract, this, _1, _2)); + &ColorHistogram::extract, this, boost::placeholders::_1, boost::placeholders::_2)); } else { it_.reset(new image_transport::ImageTransport(nh_)); @@ -115,7 +115,7 @@ namespace jsk_perception mask_sync_->connectInput(image_sub_, image_mask_sub_); mask_sync_->registerCallback( boost::bind( - &ColorHistogram::extractMask, this, _1, _2)); + &ColorHistogram::extractMask, this, boost::placeholders::_1, boost::placeholders::_2)); } jsk_topic_tools::warnNoRemap(names); } diff --git a/jsk_perception/src/color_histogram_label_match.cpp b/jsk_perception/src/color_histogram_label_match.cpp index d22637d4a5..d176a1ab4a 100644 --- a/jsk_perception/src/color_histogram_label_match.cpp +++ b/jsk_perception/src/color_histogram_label_match.cpp @@ -48,7 +48,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &ColorHistogramLabelMatch::configCallback, this, _1, _2); + &ColorHistogramLabelMatch::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("use_mask", use_mask_, false); pub_debug_ = advertise( @@ -84,14 +84,14 @@ namespace jsk_perception sync_->connectInput(sub_image_, sub_label_, sub_mask_); sync_->registerCallback( boost::bind( - &ColorHistogramLabelMatch::match, this, _1, _2, _3)); + &ColorHistogramLabelMatch::match, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_wo_mask_ = boost::make_shared >(100); sync_wo_mask_->connectInput(sub_image_, sub_label_); sync_wo_mask_->registerCallback( boost::bind( - &ColorHistogramLabelMatch::match, this, _1, _2)); + &ColorHistogramLabelMatch::match, this, boost::placeholders::_1, boost::placeholders::_2)); } sub_histogram_ = pnh_->subscribe( "input/histogram", 1, &ColorHistogramLabelMatch::histogramCallback, this); diff --git a/jsk_perception/src/color_histogram_sliding_matcher.cpp b/jsk_perception/src/color_histogram_sliding_matcher.cpp index 596580983f..c436ade813 100644 --- a/jsk_perception/src/color_histogram_sliding_matcher.cpp +++ b/jsk_perception/src/color_histogram_sliding_matcher.cpp @@ -101,7 +101,7 @@ class MatcherNode _debug_pub = _it.advertise("debug_image", 1); // _subImage = _it.subscribe("image", 1, &MatcherNode::image_cb, this); - sync.registerCallback( boost::bind (&MatcherNode::image_cb , this, _1, _2) ); + sync.registerCallback( boost::bind (&MatcherNode::image_cb , this, boost::placeholders::_1, boost::placeholders::_2) ); ros::NodeHandle local_nh("~"); @@ -442,7 +442,7 @@ int main(int argc, char **argv){ dynamic_reconfigure::Server server; dynamic_reconfigure::Server::CallbackType f; - f = boost::bind(&MatcherNode::dyn_conf_callback, &matcher, _1, _2); + f = boost::bind(&MatcherNode::dyn_conf_callback, &matcher, boost::placeholders::_1, boost::placeholders::_2); server.setCallback(f); ros::spin(); return 0; diff --git a/jsk_perception/src/concave_hull_mask_image.cpp b/jsk_perception/src/concave_hull_mask_image.cpp index 61b5242dfc..e8e0bd676a 100644 --- a/jsk_perception/src/concave_hull_mask_image.cpp +++ b/jsk_perception/src/concave_hull_mask_image.cpp @@ -48,7 +48,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ConcaveHullMaskImage::configCallback, this, _1, _2); + boost::bind (&ConcaveHullMaskImage::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/consensus_tracking.cpp b/jsk_perception/src/consensus_tracking.cpp index fa596a4dd6..6a8950b8f4 100644 --- a/jsk_perception/src/consensus_tracking.cpp +++ b/jsk_perception/src/consensus_tracking.cpp @@ -64,13 +64,13 @@ namespace jsk_perception { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_image_to_init_, sub_polygon_to_init_); - async_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2)); + async_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_image_to_init_, sub_polygon_to_init_); - sync_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, _1, _2)); + sync_->registerCallback(boost::bind(&ConsensusTracking::setInitialWindow, this, boost::placeholders::_1, boost::placeholders::_2)); } onInitPostProcess(); diff --git a/jsk_perception/src/draw_rects.cpp b/jsk_perception/src/draw_rects.cpp index 4307cb4d89..cfda57fb0e 100644 --- a/jsk_perception/src/draw_rects.cpp +++ b/jsk_perception/src/draw_rects.cpp @@ -53,7 +53,7 @@ namespace jsk_perception srv_ = boost::make_shared >(*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind(&DrawRects::configCallback, this, _1, _2); + boost::bind(&DrawRects::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_image_ = advertise(*pnh_, "output", 1); @@ -81,7 +81,7 @@ namespace jsk_perception if (use_classification_result_) sub_class_.subscribe(*pnh_, "input/class", 1); else - sub_rects_.registerCallback(boost::bind(&DrawRects::fillEmptyClasses, this, _1)); + sub_rects_.registerCallback(boost::bind(&DrawRects::fillEmptyClasses, this, boost::placeholders::_1)); if (use_async_) { @@ -90,14 +90,14 @@ namespace jsk_perception async_->connectInput(sub_image_, sub_rects_, sub_class_); else async_->connectInput(sub_image_, sub_rects_, null_class_); - async_->registerCallback(boost::bind(&DrawRects::onMessage, this, _1, _2, _3)); + async_->registerCallback(boost::bind(&DrawRects::onMessage, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_ = boost::make_shared >(queue_size_); if (use_classification_result_) sync_->connectInput(sub_image_, sub_rects_, sub_class_); else sync_->connectInput(sub_image_, sub_rects_, null_class_); - sync_->registerCallback(boost::bind(&DrawRects::onMessage, this, _1, _2, _3)); + sync_->registerCallback(boost::bind(&DrawRects::onMessage, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } } diff --git a/jsk_perception/src/dual_fisheye_to_panorama.cpp b/jsk_perception/src/dual_fisheye_to_panorama.cpp index 4037ac1c1d..88208b65f1 100644 --- a/jsk_perception/src/dual_fisheye_to_panorama.cpp +++ b/jsk_perception/src/dual_fisheye_to_panorama.cpp @@ -84,7 +84,7 @@ namespace jsk_perception sticher_initialized_ = false; srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&DualFisheyeToPanorama::configCallback, this, _1, _2); + boost::bind (&DualFisheyeToPanorama::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); msg_panorama_info_.projection_model = "equirectangular"; diff --git a/jsk_perception/src/filter_mask_image_with_size.cpp b/jsk_perception/src/filter_mask_image_with_size.cpp index 3a66f005d1..a273fef834 100644 --- a/jsk_perception/src/filter_mask_image_with_size.cpp +++ b/jsk_perception/src/filter_mask_image_with_size.cpp @@ -49,7 +49,7 @@ namespace jsk_perception pnh_->param("use_reference", use_reference_, false); srv_ = boost::make_shared >(*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&FilterMaskImageWithSize::configCallback, this, _1, _2); + boost::bind(&FilterMaskImageWithSize::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); @@ -101,13 +101,13 @@ namespace jsk_perception { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_input_, sub_reference_); - async_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, _1, _2)); + async_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_input_, sub_reference_); - sync_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, _1, _2)); + sync_->registerCallback(boost::bind(&FilterMaskImageWithSize::filter, this, boost::placeholders::_1, boost::placeholders::_2)); } names.push_back("~input/reference"); } diff --git a/jsk_perception/src/fisheye_to_panorama.cpp b/jsk_perception/src/fisheye_to_panorama.cpp index 2041fa5e1c..d75f51308c 100644 --- a/jsk_perception/src/fisheye_to_panorama.cpp +++ b/jsk_perception/src/fisheye_to_panorama.cpp @@ -58,7 +58,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&FisheyeToPanorama::configCallback, this, _1, _2); + boost::bind (&FisheyeToPanorama::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); scale_ = 0.5; diff --git a/jsk_perception/src/flow_velocity_thresholding.cpp b/jsk_perception/src/flow_velocity_thresholding.cpp index 9052a7ee8e..be2a7d70f0 100644 --- a/jsk_perception/src/flow_velocity_thresholding.cpp +++ b/jsk_perception/src/flow_velocity_thresholding.cpp @@ -49,7 +49,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&FlowVelocityThresholding::configCallback, this, _1, _2); + boost::bind (&FlowVelocityThresholding::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("approximate_sync", approximate_sync_, false); pnh_->param("queue_size", queue_size_, 100); @@ -88,12 +88,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_flow_, sub_info_); - async_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2)); + async_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_flow_, sub_info_); - sync_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2)); + sync_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, boost::placeholders::_1, boost::placeholders::_2)); } names.push_back("~input/camera_info"); } diff --git a/jsk_perception/src/gaussian_blur.cpp b/jsk_perception/src/gaussian_blur.cpp index f9e586771c..a98a39804c 100644 --- a/jsk_perception/src/gaussian_blur.cpp +++ b/jsk_perception/src/gaussian_blur.cpp @@ -48,7 +48,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&GaussianBlur::configCallback, this, _1, _2); + boost::bind (&GaussianBlur::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/grabcut_nodelet.cpp b/jsk_perception/src/grabcut_nodelet.cpp index 406f5fe151..7680488870 100644 --- a/jsk_perception/src/grabcut_nodelet.cpp +++ b/jsk_perception/src/grabcut_nodelet.cpp @@ -46,7 +46,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &GrabCut::configCallback, this, _1, _2); + &GrabCut::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_foreground_ = advertise(*pnh_, "output/foreground", 1); @@ -78,7 +78,7 @@ namespace jsk_perception sync_ = boost::make_shared >(100); sync_->connectInput(sub_image_, sub_foreground_, sub_background_); sync_->registerCallback(boost::bind(&GrabCut::segment, - this, _1, _2, _3)); + this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } void GrabCut::unsubscribe() diff --git a/jsk_perception/src/grid_label.cpp b/jsk_perception/src/grid_label.cpp index dff57d3176..4c8d71df7e 100644 --- a/jsk_perception/src/grid_label.cpp +++ b/jsk_perception/src/grid_label.cpp @@ -51,7 +51,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&GridLabel::configCallback, this, _1, _2); + boost::bind (&GridLabel::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_->param("use_camera_info", use_camera_info_, false); diff --git a/jsk_perception/src/kmeans.cpp b/jsk_perception/src/kmeans.cpp index 29c8dab8af..bfda056147 100644 --- a/jsk_perception/src/kmeans.cpp +++ b/jsk_perception/src/kmeans.cpp @@ -49,7 +49,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&KMeans::configCallback, this, _1, _2); + boost::bind (&KMeans::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/label_to_mask_image.cpp b/jsk_perception/src/label_to_mask_image.cpp index f9e332cb9c..ba245fbbcf 100644 --- a/jsk_perception/src/label_to_mask_image.cpp +++ b/jsk_perception/src/label_to_mask_image.cpp @@ -48,7 +48,7 @@ namespace jsk_perception // dynamic_reconfigure srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&LabelToMaskImage::configCallback, this, _1, _2); + boost::bind(&LabelToMaskImage::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/mask_image_generator.cpp b/jsk_perception/src/mask_image_generator.cpp index 38d94f4ca8..08cef8d075 100644 --- a/jsk_perception/src/mask_image_generator.cpp +++ b/jsk_perception/src/mask_image_generator.cpp @@ -51,7 +51,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&MaskImageGenerator::configCallback, this, _1, _2); + boost::bind (&MaskImageGenerator::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/mask_image_to_rect.cpp b/jsk_perception/src/mask_image_to_rect.cpp index 9fcfd57b99..857a6e9993 100644 --- a/jsk_perception/src/mask_image_to_rect.cpp +++ b/jsk_perception/src/mask_image_to_rect.cpp @@ -48,7 +48,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared >(*pnh_); typename dynamic_reconfigure::Server::CallbackType f = - boost::bind(&MaskImageToRect::configCallback, this, _1, _2); + boost::bind(&MaskImageToRect::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback(f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/morphological_operator.cpp b/jsk_perception/src/morphological_operator.cpp index 0c24af6739..9bd633d35a 100644 --- a/jsk_perception/src/morphological_operator.cpp +++ b/jsk_perception/src/morphological_operator.cpp @@ -50,7 +50,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &MorphologicalImageOperatorNodelet::configCallback, this, _1, _2); + &MorphologicalImageOperatorNodelet::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/multiply_mask_image.cpp b/jsk_perception/src/multiply_mask_image.cpp index 1f509a4425..b1fcabc341 100644 --- a/jsk_perception/src/multiply_mask_image.cpp +++ b/jsk_perception/src/multiply_mask_image.cpp @@ -71,12 +71,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_src1_, sub_src2_); - async_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, _1, _2)); + async_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_src1_, sub_src2_); - sync_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, _1, _2)); + sync_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input/src1")("~input/src2"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/overlay_image_color_on_mono.cpp b/jsk_perception/src/overlay_image_color_on_mono.cpp index 8172fcdecb..67d137136d 100644 --- a/jsk_perception/src/overlay_image_color_on_mono.cpp +++ b/jsk_perception/src/overlay_image_color_on_mono.cpp @@ -52,7 +52,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &OverlayImageColorOnMono::configCallback, this, _1, _2); + &OverlayImageColorOnMono::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); @@ -83,11 +83,11 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_color_, sub_mono_); - async_->registerCallback(boost::bind(&OverlayImageColorOnMono::overlay, this, _1, _2)); + async_->registerCallback(boost::bind(&OverlayImageColorOnMono::overlay, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_color_, sub_mono_); - sync_->registerCallback(boost::bind(&OverlayImageColorOnMono::overlay, this, _1, _2)); + sync_->registerCallback(boost::bind(&OverlayImageColorOnMono::overlay, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input/color")("~input/mono"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/point_pose_extractor.cpp b/jsk_perception/src/point_pose_extractor.cpp index 3a49185548..342becd48e 100644 --- a/jsk_perception/src/point_pose_extractor.cpp +++ b/jsk_perception/src/point_pose_extractor.cpp @@ -340,7 +340,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); dynamic_reconfigure::Server server; dynamic_reconfigure::Server::CallbackType f; - f = boost::bind(&PointPoseExtractor::dyn_conf_callback, this, _1, _2); + f = boost::bind(&PointPoseExtractor::dyn_conf_callback, this, boost::placeholders::_1, boost::placeholders::_2); server.setCallback(f); it = new image_transport::ImageTransport(*pnh_); diff --git a/jsk_perception/src/polygon_array_color_histogram.cpp b/jsk_perception/src/polygon_array_color_histogram.cpp index bb9813b225..51752f65c0 100644 --- a/jsk_perception/src/polygon_array_color_histogram.cpp +++ b/jsk_perception/src/polygon_array_color_histogram.cpp @@ -55,7 +55,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &PolygonArrayColorHistogram::configCallback, this, _1, _2); + &PolygonArrayColorHistogram::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); pub_debug_polygon_ = advertise(*pnh_, "debug/polygon_image", 1); @@ -81,7 +81,7 @@ namespace jsk_perception async_ = boost::make_shared >(sync_queue_size_); async_->connectInput(sub_image_, sub_polygon_); async_->registerCallback( - boost::bind(&PolygonArrayColorHistogram::compute, this, _1, _2)); + boost::bind(&PolygonArrayColorHistogram::compute, this, boost::placeholders::_1, boost::placeholders::_2)); } void PolygonArrayColorHistogram::unsubscribe() diff --git a/jsk_perception/src/polygon_array_color_likelihood.cpp b/jsk_perception/src/polygon_array_color_likelihood.cpp index ea488a25d4..ae57f38853 100644 --- a/jsk_perception/src/polygon_array_color_likelihood.cpp +++ b/jsk_perception/src/polygon_array_color_likelihood.cpp @@ -56,7 +56,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &PolygonArrayColorLikelihood::configCallback, this, _1, _2); + &PolygonArrayColorLikelihood::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); onInitPostProcess(); @@ -86,13 +86,13 @@ namespace jsk_perception async_ = boost::make_shared >(sync_queue_size_); async_->connectInput(sub_polygon_, sub_histogram_); async_->registerCallback( - boost::bind(&PolygonArrayColorLikelihood::likelihood, this, _1, _2)); + boost::bind(&PolygonArrayColorLikelihood::likelihood, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(sync_queue_size_); sync_->connectInput(sub_polygon_, sub_histogram_); sync_->registerCallback( - boost::bind(&PolygonArrayColorLikelihood::likelihood, this, _1, _2)); + boost::bind(&PolygonArrayColorLikelihood::likelihood, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_perception/src/project_image_point.cpp b/jsk_perception/src/project_image_point.cpp index 205586134c..574e7454a0 100644 --- a/jsk_perception/src/project_image_point.cpp +++ b/jsk_perception/src/project_image_point.cpp @@ -44,7 +44,7 @@ namespace jsk_perception DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind (&ProjectImagePoint::configCallback, this, _1, _2); + boost::bind (&ProjectImagePoint::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/rect_array_actual_size_filter.cpp b/jsk_perception/src/rect_array_actual_size_filter.cpp index b3dae11700..bf76a08e55 100644 --- a/jsk_perception/src/rect_array_actual_size_filter.cpp +++ b/jsk_perception/src/rect_array_actual_size_filter.cpp @@ -47,7 +47,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &RectArrayActualSizeFilter::configCallback, this, _1, _2); + &RectArrayActualSizeFilter::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise( @@ -75,12 +75,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(100); async_->connectInput(sub_rect_array_, sub_image_, sub_info_); - async_->registerCallback(boost::bind(&RectArrayActualSizeFilter::filter, this, _1, _2, _3)); + async_->registerCallback(boost::bind(&RectArrayActualSizeFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_rect_array_, sub_image_, sub_info_); - sync_->registerCallback(boost::bind(&RectArrayActualSizeFilter::filter, this, _1, _2, _3)); + sync_->registerCallback(boost::bind(&RectArrayActualSizeFilter::filter, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3)); } } diff --git a/jsk_perception/src/rect_array_to_density_image.cpp b/jsk_perception/src/rect_array_to_density_image.cpp index b45ec69573..10859ad27b 100644 --- a/jsk_perception/src/rect_array_to_density_image.cpp +++ b/jsk_perception/src/rect_array_to_density_image.cpp @@ -70,12 +70,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_image_, sub_rects_); - async_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2)); + async_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_image_, sub_rects_); - sync_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2)); + sync_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input/image")("~input/rect_array"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/rectangle_detector.cpp b/jsk_perception/src/rectangle_detector.cpp index c5c5c42c93..ffbc3c7930 100644 --- a/jsk_perception/src/rectangle_detector.cpp +++ b/jsk_perception/src/rectangle_detector.cpp @@ -193,11 +193,11 @@ class RectangleDetector image_sub = new message_filters::Subscriber(nh_, "image", 1); line_sub = new message_filters::Subscriber(nh_, "lines", 1); sync = new TimeSynchronizer(*image_sub, *line_sub, 10); - sync->registerCallback(boost::bind(&RectangleDetector::callback, this, _1, _2)); + sync->registerCallback(boost::bind(&RectangleDetector::callback, this, boost::placeholders::_1, boost::placeholders::_2)); image_pub_ = nh_.advertise("rectangle/image", 1); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&RectangleDetector::reconfigureCallback, this, _1, _2); + boost::bind(&RectangleDetector::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv.setCallback(f); } }; diff --git a/jsk_perception/src/remove_blurred_frames.cpp b/jsk_perception/src/remove_blurred_frames.cpp index d4e8dcd119..1b7cd6d95e 100644 --- a/jsk_perception/src/remove_blurred_frames.cpp +++ b/jsk_perception/src/remove_blurred_frames.cpp @@ -44,7 +44,7 @@ namespace jsk_perception{ DiagnosticNodelet::onInit(); srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&RemoveBlurredFrames::configCallback, this, _1, _2); + boost::bind(&RemoveBlurredFrames::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise(*pnh_, "output", 1); pub_masked_ = advertise(*pnh_, "output/mask", 1); diff --git a/jsk_perception/src/single_channel_histogram.cpp b/jsk_perception/src/single_channel_histogram.cpp index e29c8dd785..6a79712741 100644 --- a/jsk_perception/src/single_channel_histogram.cpp +++ b/jsk_perception/src/single_channel_histogram.cpp @@ -48,7 +48,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &SingleChannelHistogram::configCallback, this, _1, _2); + &SingleChannelHistogram::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_ = advertise( @@ -78,7 +78,7 @@ namespace jsk_perception sync_ = boost::make_shared >(100); sync_->connectInput(sub_image_, sub_mask_); sync_->registerCallback(boost::bind(&SingleChannelHistogram::compute, - this, _1, _2)); + this, boost::placeholders::_1, boost::placeholders::_2)); } else { sub_ = pnh_->subscribe("input", 1, diff --git a/jsk_perception/src/slic_superpixels.cpp b/jsk_perception/src/slic_superpixels.cpp index 1d384053ad..ac324176bc 100644 --- a/jsk_perception/src/slic_superpixels.cpp +++ b/jsk_perception/src/slic_superpixels.cpp @@ -50,7 +50,7 @@ namespace jsk_perception srv_ = boost::make_shared > (pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &SLICSuperPixels::configCallback, this, _1, _2); + &SLICSuperPixels::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pnh_.param("publish_debug_images", debug_image_, false); diff --git a/jsk_perception/src/sliding_window_object_detector.cpp b/jsk_perception/src/sliding_window_object_detector.cpp index 0250067a56..58cf468bc2 100644 --- a/jsk_perception/src/sliding_window_object_detector.cpp +++ b/jsk_perception/src/sliding_window_object_detector.cpp @@ -21,7 +21,7 @@ namespace jsk_perception jsk_perception::SlidingWindowObjectDetectorConfig> >(*pnh_); dynamic_reconfigure::Server< jsk_perception::SlidingWindowObjectDetectorConfig>::CallbackType f = - boost::bind(&SlidingWindowObjectDetector::configCallback, this, _1, _2); + boost::bind(&SlidingWindowObjectDetector::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); this->srv_->setCallback(f); pnh_->getParam("run_type", this->run_type_); diff --git a/jsk_perception/src/snake_segmentation.cpp b/jsk_perception/src/snake_segmentation.cpp index b5a6b30c9f..bc596d6751 100644 --- a/jsk_perception/src/snake_segmentation.cpp +++ b/jsk_perception/src/snake_segmentation.cpp @@ -51,7 +51,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &SnakeSegmentation::configCallback, this, _1, _2); + &SnakeSegmentation::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); pub_debug_ = advertise(*pnh_, "debug", 1); diff --git a/jsk_perception/src/sparse_image_decoder.cpp b/jsk_perception/src/sparse_image_decoder.cpp index 90da291ec4..1a28306812 100644 --- a/jsk_perception/src/sparse_image_decoder.cpp +++ b/jsk_perception/src/sparse_image_decoder.cpp @@ -103,8 +103,8 @@ class SparseImageDecoder: public nodelet::Nodelet _img_ptr.reset(new sensor_msgs::Image()); _it.reset(new image_transport::ImageTransport(_nh)); _subscriber_count = 0; - image_transport::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageDecoder::connectCb, this, _1); - image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageDecoder::disconnectCb, this, _1); + image_transport::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageDecoder::connectCb, this, boost::placeholders::_1); + image_transport::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageDecoder::disconnectCb, this, boost::placeholders::_1); _img_pub = image_transport::ImageTransport(ros::NodeHandle(_nh, "sparse")).advertise("image_decoded", 1, connect_cb, disconnect_cb); } // end of onInit function }; // end of SparseImageDecoder class definition diff --git a/jsk_perception/src/sparse_image_encoder.cpp b/jsk_perception/src/sparse_image_encoder.cpp index ec9f4d0bc8..e8cea7a831 100644 --- a/jsk_perception/src/sparse_image_encoder.cpp +++ b/jsk_perception/src/sparse_image_encoder.cpp @@ -110,8 +110,8 @@ class SparseImageEncoder: public nodelet::Nodelet _ln = ros::NodeHandle("~"); _it.reset(new image_transport::ImageTransport(_nh)); _subscriber_count = 0; - ros::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageEncoder::connectCb, this, _1); - ros::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageEncoder::disconnectCb, this, _1); + ros::SubscriberStatusCallback connect_cb = boost::bind(&SparseImageEncoder::connectCb, this, boost::placeholders::_1); + ros::SubscriberStatusCallback disconnect_cb = boost::bind(&SparseImageEncoder::disconnectCb, this, boost::placeholders::_1); _spr_img_pub = _nh.advertise("sparse_image", 10, connect_cb, disconnect_cb); _spr_img_ptr = boost::make_shared(); _ln.param("rate", _rate, 3.0); diff --git a/jsk_perception/src/subtract_mask_image.cpp b/jsk_perception/src/subtract_mask_image.cpp index 2f837cd90a..0894a4e868 100644 --- a/jsk_perception/src/subtract_mask_image.cpp +++ b/jsk_perception/src/subtract_mask_image.cpp @@ -76,12 +76,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(queue_size_); async_->connectInput(sub_src1_, sub_src2_); - async_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, _1, _2)); + async_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(queue_size_); sync_->connectInput(sub_src1_, sub_src2_); - sync_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, _1, _2)); + sync_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, boost::placeholders::_1, boost::placeholders::_2)); } } diff --git a/jsk_perception/src/tabletop_color_difference_likelihood.cpp b/jsk_perception/src/tabletop_color_difference_likelihood.cpp index 8df5445fe4..08c0b61e5f 100644 --- a/jsk_perception/src/tabletop_color_difference_likelihood.cpp +++ b/jsk_perception/src/tabletop_color_difference_likelihood.cpp @@ -58,7 +58,7 @@ namespace jsk_perception srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = boost::bind ( - &TabletopColorDifferenceLikelihood::configCallback, this, _1, _2); + &TabletopColorDifferenceLikelihood::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); tf_listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance(); pub_ = advertise(*pnh_, "output", 1); @@ -103,7 +103,7 @@ namespace jsk_perception *tf_listener_, msg->header.frame_id, tf_queue_size_)); - tf_filter_->registerCallback(boost::bind(&TabletopColorDifferenceLikelihood::imageCallback, this, _1)); + tf_filter_->registerCallback(boost::bind(&TabletopColorDifferenceLikelihood::imageCallback, this, boost::placeholders::_1)); } } diff --git a/jsk_perception/src/unapply_mask_image.cpp b/jsk_perception/src/unapply_mask_image.cpp index 03163da725..dbafc0a20d 100644 --- a/jsk_perception/src/unapply_mask_image.cpp +++ b/jsk_perception/src/unapply_mask_image.cpp @@ -71,12 +71,12 @@ namespace jsk_perception if (approximate_sync_) { async_ = boost::make_shared >(100); async_->connectInput(sub_image_, sub_mask_); - async_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, _1, _2)); + async_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, boost::placeholders::_1, boost::placeholders::_2)); } else { sync_ = boost::make_shared >(100); sync_->connectInput(sub_image_, sub_mask_); - sync_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, _1, _2)); + sync_->registerCallback(boost::bind(&UnapplyMaskImage::apply, this, boost::placeholders::_1, boost::placeholders::_2)); } ros::V_string names = boost::assign::list_of("~input")("~input/mask"); jsk_topic_tools::warnNoRemap(names); diff --git a/jsk_perception/src/video_to_scene.cpp b/jsk_perception/src/video_to_scene.cpp index 6d323d9cb0..4a1fbf431b 100644 --- a/jsk_perception/src/video_to_scene.cpp +++ b/jsk_perception/src/video_to_scene.cpp @@ -51,7 +51,7 @@ namespace jsk_perception{ srv_ = boost::make_shared > (*pnh_); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&VideoToScene::configCallback, this, _1, _2); + boost::bind(&VideoToScene::configCallback, this, boost::placeholders::_1, boost::placeholders::_2); srv_->setCallback (f); //pub_ = advertise(*pnh_, "output", 1); diff --git a/jsk_perception/src/virtual_camera_mono.cpp b/jsk_perception/src/virtual_camera_mono.cpp index 72848006bd..6b5e36fe9f 100644 --- a/jsk_perception/src/virtual_camera_mono.cpp +++ b/jsk_perception/src/virtual_camera_mono.cpp @@ -13,7 +13,7 @@ namespace jsk_perception pub_ = advertiseCamera(*pnh_, "image", 1); dynamic_reconfigure::Server::CallbackType f = - boost::bind(&VirtualCameraMono::configCb, this, _1, _2); + boost::bind(&VirtualCameraMono::configCb, this, boost::placeholders::_1, boost::placeholders::_2); srv_ = boost::make_shared >(*pnh_); srv_->setCallback(f); diff --git a/orbit_pantilt/src/orbit_pantilt.cpp b/orbit_pantilt/src/orbit_pantilt.cpp index 39d8199bce..2e53fc8471 100644 --- a/orbit_pantilt/src/orbit_pantilt.cpp +++ b/orbit_pantilt/src/orbit_pantilt.cpp @@ -141,7 +141,7 @@ class OrbitPanTilt { nh_.getParam("pan_ratio", pan_ratio_); nh_.getParam("tilt_ratio", tilt_ratio_); - ReconfigureServer::CallbackType f = boost::bind(&OrbitPanTilt::config_cb, this, _1, _2); + ReconfigureServer::CallbackType f = boost::bind(&OrbitPanTilt::config_cb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_.setCallback(f); ros::Publisher joint_state_pub = nh_.advertise ("joint_states", 1); diff --git a/resized_image_transport/src/image_resizer_nodelet.cpp b/resized_image_transport/src/image_resizer_nodelet.cpp index 0cf605a7c1..2c6b277eeb 100644 --- a/resized_image_transport/src/image_resizer_nodelet.cpp +++ b/resized_image_transport/src/image_resizer_nodelet.cpp @@ -25,7 +25,7 @@ namespace resized_image_transport void ImageResizer::initReconfigure() { reconfigure_server_ = boost::make_shared > (*pnh_); ReconfigureServer::CallbackType f - = boost::bind(&ImageResizer::config_cb, this, _1, _2); + = boost::bind(&ImageResizer::config_cb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_->setCallback(f); } diff --git a/resized_image_transport/src/log_polar_nodelet.cpp b/resized_image_transport/src/log_polar_nodelet.cpp index 5127f2b638..f67604755a 100644 --- a/resized_image_transport/src/log_polar_nodelet.cpp +++ b/resized_image_transport/src/log_polar_nodelet.cpp @@ -14,7 +14,7 @@ namespace resized_image_transport void LogPolar::initReconfigure(){ reconfigure_server_ = boost::make_shared > (*pnh_); ReconfigureServer::CallbackType f - = boost::bind(&LogPolar::config_cb, this, _1, _2); + = boost::bind(&LogPolar::config_cb, this, boost::placeholders::_1, boost::placeholders::_2); reconfigure_server_->setCallback(f); }