diff --git a/tf/include/tf/message_filter.h b/tf/include/tf/message_filter.h index 8d09a5cb..b8cf860f 100644 --- a/tf/include/tf/message_filter.h +++ b/tf/include/tf/message_filter.h @@ -40,7 +40,7 @@ #include #include #include -#include +#include #include #include #include @@ -302,7 +302,7 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi message_filters::Connection registerFailureCallback(const FailureCallback& callback) { boost::mutex::scoped_lock lock(failure_signal_mutex_); - return message_filters::Connection(boost::bind(&MessageFilter::disconnectFailure, this, _1), failure_signal_.connect(callback)); + return message_filters::Connection(boost::bind(&MessageFilter::disconnectFailure, this, boost::placeholders::_1), failure_signal_.connect(callback)); } virtual void setQueueSize( uint32_t new_queue_size ) diff --git a/tf/src/tf_monitor.cpp b/tf/src/tf_monitor.cpp index 878c1b46..59c0a666 100644 --- a/tf/src/tf_monitor.cpp +++ b/tf/src/tf_monitor.cpp @@ -35,7 +35,7 @@ #include "tf/tf.h" #include "tf/transform_listener.h" #include -#include +#include #include #include "ros/ros.h" @@ -168,8 +168,8 @@ class TFMonitor } cout <("tf", 100, boost::bind(&TFMonitor::callback, this, _1)); - subscriber_tf_static_ = node_.subscribe("tf_static", 100, boost::bind(&TFMonitor::static_callback, this, _1)); + subscriber_tf_ = node_.subscribe("tf", 100, boost::bind(&TFMonitor::callback, this, boost::placeholders::_1)); + subscriber_tf_static_ = node_.subscribe("tf_static", 100, boost::bind(&TFMonitor::static_callback, this, boost::placeholders::_1)); } diff --git a/tf/test/test_message_filter.cpp b/tf/test/test_message_filter.cpp index 632ec905..ddc4e520 100644 --- a/tf/test/test_message_filter.cpp +++ b/tf/test/test_message_filter.cpp @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include "ros/ros.h" @@ -72,7 +72,7 @@ TEST(MessageFilter, noTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); geometry_msgs::PointStampedPtr msg(new geometry_msgs::PointStamped); msg->header.stamp = ros::Time::now(); @@ -87,7 +87,7 @@ TEST(MessageFilter, noTransformsSameFrame) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); geometry_msgs::PointStampedPtr msg(new geometry_msgs::PointStamped); msg->header.stamp = ros::Time::now(); @@ -102,7 +102,7 @@ TEST(MessageFilter, preexistingTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); ros::Time stamp = ros::Time::now(); tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2"); @@ -122,7 +122,7 @@ TEST(MessageFilter, postTransforms) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); ros::Time stamp = ros::Time::now(); @@ -148,8 +148,8 @@ TEST(MessageFilter, queueSize) tf::TransformListener tf_client; Notification n(10); MessageFilter filter(tf_client, "frame1", 10); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); ros::Time stamp = ros::Time::now(); @@ -179,7 +179,7 @@ TEST(MessageFilter, setTargetFrame) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); filter.setTargetFrame("frame1000"); ros::Time stamp = ros::Time::now(); @@ -201,7 +201,7 @@ TEST(MessageFilter, multipleTargetFrames) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); std::vector target_frames; target_frames.push_back("frame1"); @@ -239,7 +239,7 @@ TEST(MessageFilter, tolerance) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); filter.setTolerance(offset); ros::Time stamp = ros::Time::now(); @@ -276,7 +276,7 @@ TEST(MessageFilter, maxRate) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1, ros::NodeHandle(), ros::Duration(1.0)); - filter.registerCallback(boost::bind(&Notification::notify, &n, _1)); + filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1)); ros::Time stamp = ros::Time::now(); tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2"); @@ -313,7 +313,7 @@ TEST(MessageFilter, outTheBackFailure) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); ros::Time stamp = ros::Time::now(); tf::StampedTransform transform(tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(1,2,3)), stamp, "frame1", "frame2"); @@ -335,7 +335,7 @@ TEST(MessageFilter, emptyFrameIDFailure) tf::TransformListener tf_client; Notification n(1); MessageFilter filter(tf_client, "frame1", 1); - filter.registerFailureCallback(boost::bind(&Notification::failure, &n, _1, _2)); + filter.registerFailureCallback(boost::bind(&Notification::failure, &n, boost::placeholders::_1, boost::placeholders::_2)); geometry_msgs::PointStampedPtr msg(new geometry_msgs::PointStamped); msg->header.frame_id = "";