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

---
 src/image_view/image_view.cpp                          | 2 +-
 src/rviz/default_plugin/axes_display.cpp               | 2 +-
 src/rviz/default_plugin/camera_display.cpp             | 2 +-
 src/rviz/default_plugin/depth_cloud_display.cpp        | 8 ++++----
 src/rviz/default_plugin/effort_display.cpp             | 2 +-
 src/rviz/default_plugin/grid_cells_display.cpp         | 2 +-
 src/rviz/default_plugin/grid_display.cpp               | 2 +-
 src/rviz/default_plugin/image_display.cpp              | 2 +-
 src/rviz/default_plugin/interactive_marker_display.cpp | 8 ++++----
 src/rviz/default_plugin/map_display.cpp                | 2 +-
 src/rviz/default_plugin/marker_display.cpp             | 4 ++--
 src/rviz/default_plugin/path_display.cpp               | 2 +-
 src/rviz/default_plugin/robot_model_display.cpp        | 4 ++--
 src/rviz/default_plugin/tf_display.cpp                 | 2 +-
 src/rviz/displays_panel.cpp                            | 2 +-
 src/rviz/frame_manager.h                               | 4 ++--
 src/rviz/image/image_display_base.cpp                  | 6 +++---
 src/rviz/message_filter_display.h                      | 2 +-
 src/rviz/visualization_frame.cpp                       | 2 +-
 src/rviz/visualization_manager.cpp                     | 2 +-
 src/test/rviz_logo_marker.cpp                          | 2 +-
 21 files changed, 32 insertions(+), 32 deletions(-)

diff --git a/src/image_view/image_view.cpp b/src/image_view/image_view.cpp
index 03beca3..aaf8806 100644
--- a/src/image_view/image_view.cpp
+++ b/src/image_view/image_view.cpp
@@ -94,7 +94,7 @@ void ImageView::showEvent(QShowEvent* event)
 
     texture_sub_.reset(new image_transport::SubscriberFilter());
     texture_sub_->subscribe(texture_it_, "image", 1, image_transport::TransportHints("raw"));
-    texture_sub_->registerCallback(boost::bind(&ImageView::textureCallback, this, _1));
+    texture_sub_->registerCallback(boost::bind(&ImageView::textureCallback, this, boost::placeholders::_1));
   }
   catch (ros::Exception& e)
   {
diff --git a/src/rviz/default_plugin/axes_display.cpp b/src/rviz/default_plugin/axes_display.cpp
index bc89028..d70e1da 100644
--- a/src/rviz/default_plugin/axes_display.cpp
+++ b/src/rviz/default_plugin/axes_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreSceneNode.h>
 #include <OgreSceneManager.h>
diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp
index 49abcfe..0a096f0 100644
--- a/src/rviz/default_plugin/camera_display.cpp
+++ b/src/rviz/default_plugin/camera_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreManualObject.h>
 #include <OgreMaterialManager.h>
diff --git a/src/rviz/default_plugin/depth_cloud_display.cpp b/src/rviz/default_plugin/depth_cloud_display.cpp
index bb5d7e6..2747286 100644
--- a/src/rviz/default_plugin/depth_cloud_display.cpp
+++ b/src/rviz/default_plugin/depth_cloud_display.cpp
@@ -41,7 +41,7 @@
 
 #include <tf2_ros/buffer.h>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <boost/algorithm/string/erase.hpp>
 #include <boost/foreach.hpp>
 #include <boost/shared_ptr.hpp>
@@ -306,7 +306,7 @@ void DepthCloudDisplay::subscribe()
       // subscribe to CameraInfo  topic
       std::string info_topic = image_transport::getCameraInfoTopic(depthmap_topic);
       cam_info_sub_->subscribe(threaded_nh_, info_topic, queue_size_);
-      cam_info_sub_->registerCallback(boost::bind(&DepthCloudDisplay::caminfoCallback, this, _1));
+      cam_info_sub_->registerCallback(boost::bind(&DepthCloudDisplay::caminfoCallback, this, boost::placeholders::_1));
 
       if (!color_topic.empty() && !color_transport.empty())
       {
@@ -319,13 +319,13 @@ void DepthCloudDisplay::subscribe()
         sync_depth_color_->setInterMessageLowerBound(0, ros::Duration(0.5));
         sync_depth_color_->setInterMessageLowerBound(1, ros::Duration(0.5));
         sync_depth_color_->registerCallback(
-            boost::bind(&DepthCloudDisplay::processMessage, this, _1, _2));
+            boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1, boost::placeholders::_2));
 
         pointcloud_common_->color_transformer_property_->setValue("RGB8");
       }
       else
       {
-        depthmap_tf_filter_->registerCallback(boost::bind(&DepthCloudDisplay::processMessage, this, _1));
+        depthmap_tf_filter_->registerCallback(boost::bind(&DepthCloudDisplay::processMessage, this, boost::placeholders::_1));
       }
     }
   }
diff --git a/src/rviz/default_plugin/effort_display.cpp b/src/rviz/default_plugin/effort_display.cpp
index 03d0b41..ce9bd54 100644
--- a/src/rviz/default_plugin/effort_display.cpp
+++ b/src/rviz/default_plugin/effort_display.cpp
@@ -119,7 +119,7 @@ void EffortDisplay::onInitialize()
                                                                    std::string(), 1, update_nh_);
 
   // but directly process messages
-  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, _1));
+  sub_.registerCallback(boost::bind(&EffortDisplay::incomingMessage, this, boost::placeholders::_1));
   updateHistoryLength();
 }
 
diff --git a/src/rviz/default_plugin/grid_cells_display.cpp b/src/rviz/default_plugin/grid_cells_display.cpp
index 6968046..c087746 100644
--- a/src/rviz/default_plugin/grid_cells_display.cpp
+++ b/src/rviz/default_plugin/grid_cells_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <OgreSceneNode.h>
 #include <OgreSceneManager.h>
 #include <OgreManualObject.h>
diff --git a/src/rviz/default_plugin/grid_display.cpp b/src/rviz/default_plugin/grid_display.cpp
index cb60571..a2154be 100644
--- a/src/rviz/default_plugin/grid_display.cpp
+++ b/src/rviz/default_plugin/grid_display.cpp
@@ -29,7 +29,7 @@
 
 #include <stdint.h>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreSceneNode.h>
 #include <OgreSceneManager.h>
diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp
index 3b5d50c..c2aa13c 100644
--- a/src/rviz/default_plugin/image_display.cpp
+++ b/src/rviz/default_plugin/image_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreManualObject.h>
 #include <OgreMaterialManager.h>
diff --git a/src/rviz/default_plugin/interactive_marker_display.cpp b/src/rviz/default_plugin/interactive_marker_display.cpp
index f3c559d..ec27776 100644
--- a/src/rviz/default_plugin/interactive_marker_display.cpp
+++ b/src/rviz/default_plugin/interactive_marker_display.cpp
@@ -109,10 +109,10 @@ void InteractiveMarkerDisplay::onInitialize()
   auto tf = context_->getFrameManager()->getTF2BufferPtr();
   im_client_.reset(new interactive_markers::InteractiveMarkerClient(*tf, fixed_frame_.toStdString()));
 
-  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, _1));
-  im_client_->setUpdateCb(boost::bind(&InteractiveMarkerDisplay::updateCb, this, _1));
-  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, _1));
-  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, _1, _2, _3));
+  im_client_->setInitCb(boost::bind(&InteractiveMarkerDisplay::initCb, this, boost::placeholders::_1));
+  im_client_->setUpdateCb(boost::bind(&InteractiveMarkerDisplay::updateCb, this, boost::placeholders::_1));
+  im_client_->setResetCb(boost::bind(&InteractiveMarkerDisplay::resetCb, this, boost::placeholders::_1));
+  im_client_->setStatusCb(boost::bind(&InteractiveMarkerDisplay::statusCb, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
 
   client_id_ = ros::this_node::getName() + "/" + getNameStd();
 
diff --git a/src/rviz/default_plugin/map_display.cpp b/src/rviz/default_plugin/map_display.cpp
index 7e4cbb4..45ace0d 100644
--- a/src/rviz/default_plugin/map_display.cpp
+++ b/src/rviz/default_plugin/map_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreManualObject.h>
 #include <OgreMaterialManager.h>
diff --git a/src/rviz/default_plugin/marker_display.cpp b/src/rviz/default_plugin/marker_display.cpp
index 79edefd..e46176c 100644
--- a/src/rviz/default_plugin/marker_display.cpp
+++ b/src/rviz/default_plugin/marker_display.cpp
@@ -75,8 +75,8 @@ void MarkerDisplay::onInitialize()
                                                              queue_size_property_->getInt(), update_nh_);
 
   tf_filter_->connectInput(sub_);
-  tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, _1));
-  tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, _1, _2));
+  tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, boost::placeholders::_1));
+  tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, boost::placeholders::_1, boost::placeholders::_2));
 
   namespace_config_enabled_state_.clear();
 }
diff --git a/src/rviz/default_plugin/path_display.cpp b/src/rviz/default_plugin/path_display.cpp
index 5c6b3d0..5968a15 100644
--- a/src/rviz/default_plugin/path_display.cpp
+++ b/src/rviz/default_plugin/path_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreSceneNode.h>
 #include <OgreSceneManager.h>
diff --git a/src/rviz/default_plugin/robot_model_display.cpp b/src/rviz/default_plugin/robot_model_display.cpp
index 4de8b0e..4c6f7ec 100644
--- a/src/rviz/default_plugin/robot_model_display.cpp
+++ b/src/rviz/default_plugin/robot_model_display.cpp
@@ -193,7 +193,7 @@ void RobotModelDisplay::load()
   setStatus(StatusProperty::Ok, "URDF", "URDF parsed OK");
   robot_->load(descr);
   robot_->update(TFLinkUpdater(context_->getFrameManager(),
-                               boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
+                               boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, this),
                                tf_prefix_property_->getStdString()));
 }
 
@@ -218,7 +218,7 @@ void RobotModelDisplay::update(float wall_dt, float /*ros_dt*/)
   if (has_new_transforms_ || update)
   {
     robot_->update(TFLinkUpdater(context_->getFrameManager(),
-                                 boost::bind(linkUpdaterStatusFunction, _1, _2, _3, this),
+                                 boost::bind(linkUpdaterStatusFunction, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, this),
                                  tf_prefix_property_->getStdString()));
     context_->queueRender();
 
diff --git a/src/rviz/default_plugin/tf_display.cpp b/src/rviz/default_plugin/tf_display.cpp
index 3ff7dc9..59d4b7d 100644
--- a/src/rviz/default_plugin/tf_display.cpp
+++ b/src/rviz/default_plugin/tf_display.cpp
@@ -27,7 +27,7 @@
  * POSSIBILITY OF SUCH DAMAGE.
  */
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreSceneNode.h>
 #include <OgreSceneManager.h>
diff --git a/src/rviz/displays_panel.cpp b/src/rviz/displays_panel.cpp
index 4abad53..eb6dcb1 100644
--- a/src/rviz/displays_panel.cpp
+++ b/src/rviz/displays_panel.cpp
@@ -34,7 +34,7 @@
 #include <QInputDialog>
 #include <QApplication>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <rviz/display_factory.h>
 #include <rviz/display.h>
diff --git a/src/rviz/frame_manager.h b/src/rviz/frame_manager.h
index f17da06..b00d263 100644
--- a/src/rviz/frame_manager.h
+++ b/src/rviz/frame_manager.h
@@ -192,9 +192,9 @@ public:
   template <class M>
   void registerFilterForTransformStatusCheck(tf2_ros::MessageFilter<M>* filter, Display* display)
   {
-    filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, _1, display));
+    filter->registerCallback(boost::bind(&FrameManager::messageCallback<M>, this, boost::placeholders::_1, display));
     filter->registerFailureCallback(boost::bind(
-        &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, _1, _2, display));
+        &FrameManager::failureCallback<M, tf2_ros::FilterFailureReason>, this, boost::placeholders::_1, boost::placeholders::_2, display));
   }
 
   /** @brief Return the current fixed frame name. */
diff --git a/src/rviz/image/image_display_base.cpp b/src/rviz/image/image_display_base.cpp
index b6e7e75..f2323d8 100644
--- a/src/rviz/image/image_display_base.cpp
+++ b/src/rviz/image/image_display_base.cpp
@@ -182,15 +182,15 @@ void ImageDisplayBase::subscribe()
 
       if (targetFrame_.empty())
       {
-        sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
+        sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
       }
       else
       {
         tf_filter_.reset(new tf2_ros::MessageFilter<sensor_msgs::Image>(
             *sub_, *context_->getTF2BufferPtr(), targetFrame_, queue_size_property_->getInt(),
             update_nh_));
-        tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
-        tf_filter_->registerFailureCallback(boost::bind(&ImageDisplayBase::failedMessage, this, _1, _2));
+        tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, boost::placeholders::_1));
+        tf_filter_->registerFailureCallback(boost::bind(&ImageDisplayBase::failedMessage, this, boost::placeholders::_1, boost::placeholders::_2));
       }
     }
     setStatus(StatusProperty::Ok, "Topic", "OK");
diff --git a/src/rviz/message_filter_display.h b/src/rviz/message_filter_display.h
index dfaa3f0..aac7b34 100644
--- a/src/rviz/message_filter_display.h
+++ b/src/rviz/message_filter_display.h
@@ -111,7 +111,7 @@ public:
 
     tf_filter_->connectInput(sub_);
     tf_filter_->registerCallback(
-        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, _1));
+        boost::bind(&MessageFilterDisplay<MessageType>::incomingMessage, this, boost::placeholders::_1));
     context_->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter_, this);
   }
 
diff --git a/src/rviz/visualization_frame.cpp b/src/rviz/visualization_frame.cpp
index 1af9ee4..00372b9 100644
--- a/src/rviz/visualization_frame.cpp
+++ b/src/rviz/visualization_frame.cpp
@@ -52,7 +52,7 @@
 
 #include <boost/algorithm/string/split.hpp>
 #include <boost/algorithm/string/trim.hpp>
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 #include <boost/filesystem.hpp>
 
 #include <ros/console.h>
diff --git a/src/rviz/visualization_manager.cpp b/src/rviz/visualization_manager.cpp
index bc98c8d..cacd2b9 100644
--- a/src/rviz/visualization_manager.cpp
+++ b/src/rviz/visualization_manager.cpp
@@ -35,7 +35,7 @@
 #include <QTimer>
 #include <QWindow>
 
-#include <boost/bind.hpp>
+#include <boost/bind/bind.hpp>
 
 #include <OgreRoot.h>
 #include <OgreSceneManager.h>
diff --git a/src/test/rviz_logo_marker.cpp b/src/test/rviz_logo_marker.cpp
index 6ff8746..d66686d 100644
--- a/src/test/rviz_logo_marker.cpp
+++ b/src/test/rviz_logo_marker.cpp
@@ -99,7 +99,7 @@ int main(int argc, char** argv)
   ros::init(argc, argv, "rviz_logo_marker");
   ros::NodeHandle n;
 
-  ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, _1));
+  ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), boost::bind(&publishCallback, boost::placeholders::_1));
 
   server = new interactive_markers::InteractiveMarkerServer("rviz_logo");
   makeMarker();
