From: Jochen Sprickerhof <jspricke@debian.org>
Date: Tue, 15 Dec 2020 11:25:56 +0100
Subject: Switch to new boost/bind/bind.hpp

---
 depth_image_proc/src/nodelets/disparity.cpp               | 2 +-
 depth_image_proc/src/nodelets/point_cloud_xyzi.cpp        | 2 +-
 depth_image_proc/src/nodelets/point_cloud_xyzi_radial.cpp | 2 +-
 depth_image_proc/src/nodelets/point_cloud_xyzrgb.cpp      | 4 ++--
 depth_image_proc/src/nodelets/register.cpp                | 2 +-
 image_proc/src/nodelets/crop_decimate.cpp                 | 2 +-
 image_proc/src/nodelets/debayer.cpp                       | 2 +-
 image_proc/src/nodelets/rectify.cpp                       | 2 +-
 image_publisher/src/nodelet/image_publisher_nodelet.cpp   | 2 +-
 image_rotate/src/nodelet/image_rotate_nodelet.cpp         | 6 +++---
 image_view/src/nodelets/image_nodelet.cpp                 | 4 ++--
 image_view/src/nodes/image_saver.cpp                      | 2 +-
 image_view/src/nodes/stereo_view.cpp                      | 4 ++--
 stereo_image_proc/src/nodelets/disparity.cpp              | 6 +++---
 stereo_image_proc/src/nodelets/point_cloud2.cpp           | 4 ++--
 15 files changed, 23 insertions(+), 23 deletions(-)

diff --git a/depth_image_proc/src/nodelets/disparity.cpp b/depth_image_proc/src/nodelets/disparity.cpp
index dd82537..e7ec4a7 100644
--- a/depth_image_proc/src/nodelets/disparity.cpp
+++ b/depth_image_proc/src/nodelets/disparity.cpp
@@ -94,7 +94,7 @@ void DisparityNodelet::onInit()
 
   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
   sync_.reset( new Sync(sub_depth_image_, sub_info_, queue_size) );
-  sync_->registerCallback(boost::bind(&DisparityNodelet::depthCb, this, _1, _2));
+  sync_->registerCallback(boost::bind(&DisparityNodelet::depthCb, this, boost::placeholders::_1, boost::placeholders::_2));
 
   // Monitor whether anyone is subscribed to the output
   ros::SubscriberStatusCallback connect_cb = boost::bind(&DisparityNodelet::connectCb, this);
diff --git a/depth_image_proc/src/nodelets/point_cloud_xyzi.cpp b/depth_image_proc/src/nodelets/point_cloud_xyzi.cpp
index d34f74d..78a96df 100644
--- a/depth_image_proc/src/nodelets/point_cloud_xyzi.cpp
+++ b/depth_image_proc/src/nodelets/point_cloud_xyzi.cpp
@@ -104,7 +104,7 @@ void PointCloudXyziNodelet::onInit()
 
   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
   sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_, sub_intensity_, sub_info_) );
-  sync_->registerCallback(boost::bind(&PointCloudXyziNodelet::imageCb, this, _1, _2, _3));
+  sync_->registerCallback(boost::bind(&PointCloudXyziNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
   
   // Monitor whether anyone is subscribed to the output
   ros::SubscriberStatusCallback connect_cb = boost::bind(&PointCloudXyziNodelet::connectCb, this);
diff --git a/depth_image_proc/src/nodelets/point_cloud_xyzi_radial.cpp b/depth_image_proc/src/nodelets/point_cloud_xyzi_radial.cpp
index 5a725e0..f626167 100644
--- a/depth_image_proc/src/nodelets/point_cloud_xyzi_radial.cpp
+++ b/depth_image_proc/src/nodelets/point_cloud_xyzi_radial.cpp
@@ -155,7 +155,7 @@ namespace depth_image_proc {
 
 	// Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
 	sync_.reset( new Synchronizer(SyncPolicy(queue_size_), sub_depth_, sub_intensity_, sub_info_) );
-	sync_->registerCallback(boost::bind(&PointCloudXyziRadialNodelet::imageCb, this, _1, _2, _3));
+	sync_->registerCallback(boost::bind(&PointCloudXyziRadialNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
     
 	// Monitor whether anyone is subscribed to the output
 	ros::SubscriberStatusCallback connect_cb = 
diff --git a/depth_image_proc/src/nodelets/point_cloud_xyzrgb.cpp b/depth_image_proc/src/nodelets/point_cloud_xyzrgb.cpp
index bd680aa..efcb26e 100644
--- a/depth_image_proc/src/nodelets/point_cloud_xyzrgb.cpp
+++ b/depth_image_proc/src/nodelets/point_cloud_xyzrgb.cpp
@@ -113,12 +113,12 @@ void PointCloudXyzrgbNodelet::onInit()
   if (use_exact_sync)
   {
     exact_sync_.reset( new ExactSynchronizer(ExactSyncPolicy(queue_size), sub_depth_, sub_rgb_, sub_info_) );
-    exact_sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, _1, _2, _3));
+    exact_sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
   }
   else
   {
     sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_, sub_rgb_, sub_info_) );
-    sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, _1, _2, _3));
+    sync_->registerCallback(boost::bind(&PointCloudXyzrgbNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
   }
   
   // Monitor whether anyone is subscribed to the output
diff --git a/depth_image_proc/src/nodelets/register.cpp b/depth_image_proc/src/nodelets/register.cpp
index ec0c3a4..35ee3ab 100644
--- a/depth_image_proc/src/nodelets/register.cpp
+++ b/depth_image_proc/src/nodelets/register.cpp
@@ -105,7 +105,7 @@ void RegisterNodelet::onInit()
 
   // Synchronize inputs. Topic subscriptions happen on demand in the connection callback.
   sync_.reset( new Synchronizer(SyncPolicy(queue_size), sub_depth_image_, sub_depth_info_, sub_rgb_info_) );
-  sync_->registerCallback(boost::bind(&RegisterNodelet::imageCb, this, _1, _2, _3));
+  sync_->registerCallback(boost::bind(&RegisterNodelet::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
 
   // Monitor whether anyone is subscribed to the output
   image_transport::ImageTransport it_depth_reg(ros::NodeHandle(nh, "depth_registered"));
diff --git a/image_proc/src/nodelets/crop_decimate.cpp b/image_proc/src/nodelets/crop_decimate.cpp
index 55a1f1b..e57eaea 100644
--- a/image_proc/src/nodelets/crop_decimate.cpp
+++ b/image_proc/src/nodelets/crop_decimate.cpp
@@ -92,7 +92,7 @@ void CropDecimateNodelet::onInit()
 
   // Set up dynamic reconfigure
   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
-  ReconfigureServer::CallbackType f = boost::bind(&CropDecimateNodelet::configCb, this, _1, _2);
+  ReconfigureServer::CallbackType f = boost::bind(&CropDecimateNodelet::configCb, this, boost::placeholders::_1, boost::placeholders::_2);
   reconfigure_server_->setCallback(f);
 
   // Monitor whether anyone is subscribed to the output
diff --git a/image_proc/src/nodelets/debayer.cpp b/image_proc/src/nodelets/debayer.cpp
index a958667..8e330a0 100644
--- a/image_proc/src/nodelets/debayer.cpp
+++ b/image_proc/src/nodelets/debayer.cpp
@@ -88,7 +88,7 @@ void DebayerNodelet::onInit()
 
   // Set up dynamic reconfigure
   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
-  ReconfigureServer::CallbackType f = boost::bind(&DebayerNodelet::configCb, this, _1, _2);
+  ReconfigureServer::CallbackType f = boost::bind(&DebayerNodelet::configCb, this, boost::placeholders::_1, boost::placeholders::_2);
   reconfigure_server_->setCallback(f);
 
   // Monitor whether anyone is subscribed to the output
diff --git a/image_proc/src/nodelets/rectify.cpp b/image_proc/src/nodelets/rectify.cpp
index dd2490c..2be4dfa 100644
--- a/image_proc/src/nodelets/rectify.cpp
+++ b/image_proc/src/nodelets/rectify.cpp
@@ -87,7 +87,7 @@ void RectifyNodelet::onInit()
 
   // Set up dynamic reconfigure
   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
-  ReconfigureServer::CallbackType f = boost::bind(&RectifyNodelet::configCb, this, _1, _2);
+  ReconfigureServer::CallbackType f = boost::bind(&RectifyNodelet::configCb, this, boost::placeholders::_1, boost::placeholders::_2);
   reconfigure_server_->setCallback(f);
 
   // Monitor whether anyone is subscribed to the output
diff --git a/image_publisher/src/nodelet/image_publisher_nodelet.cpp b/image_publisher/src/nodelet/image_publisher_nodelet.cpp
index e126f7b..fa5f337 100644
--- a/image_publisher/src/nodelet/image_publisher_nodelet.cpp
+++ b/image_publisher/src/nodelet/image_publisher_nodelet.cpp
@@ -187,7 +187,7 @@ public:
 
     srv.reset(new ReconfigureServer(getPrivateNodeHandle()));
     ReconfigureServer::CallbackType f =
-      boost::bind(&ImagePublisherNodelet::reconfigureCallback, this, _1, _2);
+      boost::bind(&ImagePublisherNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
     srv->setCallback(f);
   }
 };
diff --git a/image_rotate/src/nodelet/image_rotate_nodelet.cpp b/image_rotate/src/nodelet/image_rotate_nodelet.cpp
index 2fc023d..939e40a 100644
--- a/image_rotate/src/nodelet/image_rotate_nodelet.cpp
+++ b/image_rotate/src/nodelet/image_rotate_nodelet.cpp
@@ -267,12 +267,12 @@ public:
     angle_ = 0;
     prev_stamp_ = ros::Time::now();
     tf_sub_.reset(new tf2_ros::TransformListener(tf_buffer_));
-    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<image_rotate::ImageRotateConfig>::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/image_view/src/nodelets/image_nodelet.cpp b/image_view/src/nodelets/image_nodelet.cpp
index b329d9d..efe6114 100644
--- a/image_view/src/nodelets/image_nodelet.cpp
+++ b/image_view/src/nodelets/image_nodelet.cpp
@@ -42,7 +42,7 @@
 #include <opencv2/highgui/highgui.hpp>
 #include "window_thread.h"
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <boost/thread.hpp>
 #include <boost/format.hpp>
 
@@ -183,7 +183,7 @@ void ImageNodelet::onInit()
   pub_ = local_nh.advertise<sensor_msgs::Image>("output", 1);
 
   dynamic_reconfigure::Server<image_view::ImageViewConfig>::CallbackType f =
-    boost::bind(&ImageNodelet::reconfigureCb, this, _1, _2);
+    boost::bind(&ImageNodelet::reconfigureCb, this, boost::placeholders::_1, boost::placeholders::_2);
   srv_.setCallback(f);
 }
 
diff --git a/image_view/src/nodes/image_saver.cpp b/image_view/src/nodes/image_saver.cpp
index d3509c3..064af07 100644
--- a/image_view/src/nodes/image_saver.cpp
+++ b/image_view/src/nodes/image_saver.cpp
@@ -200,7 +200,7 @@ int main(int argc, char** argv)
                                                                               &callbacks);
   // Useful when CameraInfo is not being published
   image_transport::Subscriber sub_image = it.subscribe(
-      topic, 1, boost::bind(&Callbacks::callbackWithoutCameraInfo, &callbacks, _1));
+      topic, 1, boost::bind(&Callbacks::callbackWithoutCameraInfo, &callbacks, boost::placeholders::_1));
 
   ros::NodeHandle local_nh("~");
   std::string format_string;
diff --git a/image_view/src/nodes/stereo_view.cpp b/image_view/src/nodes/stereo_view.cpp
index 64a01cc..de816a0 100644
--- a/image_view/src/nodes/stereo_view.cpp
+++ b/image_view/src/nodes/stereo_view.cpp
@@ -421,13 +421,13 @@ public:
     {
       approximate_sync_.reset( new ApproximateSync(ApproximatePolicy(queue_size_),
                                                    left_sub_, right_sub_, disparity_sub_) );
-      approximate_sync_->registerCallback(boost::bind(&StereoView::imageCb, this, _1, _2, _3));
+      approximate_sync_->registerCallback(boost::bind(&StereoView::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
     }
     else
     {
       exact_sync_.reset( new ExactSync(ExactPolicy(queue_size_),
                                        left_sub_, right_sub_, disparity_sub_) );
-      exact_sync_->registerCallback(boost::bind(&StereoView::imageCb, this, _1, _2, _3));
+      exact_sync_->registerCallback(boost::bind(&StereoView::imageCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
     }
   }
 
diff --git a/stereo_image_proc/src/nodelets/disparity.cpp b/stereo_image_proc/src/nodelets/disparity.cpp
index 1c39f99..1465245 100644
--- a/stereo_image_proc/src/nodelets/disparity.cpp
+++ b/stereo_image_proc/src/nodelets/disparity.cpp
@@ -119,7 +119,7 @@ void DisparityNodelet::onInit()
                                                  sub_l_image_, sub_l_info_,
                                                  sub_r_image_, sub_r_info_) );
     approximate_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
-                                                    this, _1, _2, _3, _4));
+                                                    this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   }
   else
   {
@@ -127,12 +127,12 @@ void DisparityNodelet::onInit()
                                      sub_l_image_, sub_l_info_,
                                      sub_r_image_, sub_r_info_) );
     exact_sync_->registerCallback(boost::bind(&DisparityNodelet::imageCb,
-                                              this, _1, _2, _3, _4));
+                                              this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   }
 
   // Set up dynamic reconfiguration
   ReconfigureServer::CallbackType f = boost::bind(&DisparityNodelet::configCb,
-                                                  this, _1, _2);
+                                                  this, boost::placeholders::_1, boost::placeholders::_2);
   reconfigure_server_.reset(new ReconfigureServer(config_mutex_, private_nh));
   reconfigure_server_->setCallback(f);
 
diff --git a/stereo_image_proc/src/nodelets/point_cloud2.cpp b/stereo_image_proc/src/nodelets/point_cloud2.cpp
index fae8ba1..560d855 100644
--- a/stereo_image_proc/src/nodelets/point_cloud2.cpp
+++ b/stereo_image_proc/src/nodelets/point_cloud2.cpp
@@ -108,7 +108,7 @@ void PointCloud2Nodelet::onInit()
                                                  sub_l_image_, sub_l_info_,
                                                  sub_r_info_, sub_disparity_) );
     approximate_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
-                                                    this, _1, _2, _3, _4));
+                                                    this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   }
   else
   {
@@ -116,7 +116,7 @@ void PointCloud2Nodelet::onInit()
                                      sub_l_image_, sub_l_info_,
                                      sub_r_info_, sub_disparity_) );
     exact_sync_->registerCallback(boost::bind(&PointCloud2Nodelet::imageCb,
-                                              this, _1, _2, _3, _4));
+                                              this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
   }
 
   // Monitor whether anyone is subscribed to the output
