Skip to content

Commit

Permalink
Switch to new boost/bind/bind.hpp
Browse files Browse the repository at this point in the history
  • Loading branch information
jspricke committed Feb 18, 2022
1 parent 63c3c7b commit e91a32a
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 18 deletions.
4 changes: 2 additions & 2 deletions tf/include/tf/message_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@
#include <list>
#include <vector>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <boost/bind/bind.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/thread.hpp>
Expand Down Expand Up @@ -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 )
Expand Down
6 changes: 3 additions & 3 deletions tf/src/tf_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
#include "tf/tf.h"
#include "tf/transform_listener.h"
#include <string>
#include <boost/bind.hpp>
#include <boost/bind/bind.hpp>
#include <boost/thread.hpp>
#include "ros/ros.h"

Expand Down Expand Up @@ -168,8 +168,8 @@ class TFMonitor
}
cout <<endl;*/
}
subscriber_tf_ = node_.subscribe<tf::tfMessage>("tf", 100, boost::bind(&TFMonitor::callback, this, _1));
subscriber_tf_static_ = node_.subscribe<tf::tfMessage>("tf_static", 100, boost::bind(&TFMonitor::static_callback, this, _1));
subscriber_tf_ = node_.subscribe<tf::tfMessage>("tf", 100, boost::bind(&TFMonitor::callback, this, boost::placeholders::_1));
subscriber_tf_static_ = node_.subscribe<tf::tfMessage>("tf_static", 100, boost::bind(&TFMonitor::static_callback, this, boost::placeholders::_1));

}

Expand Down
26 changes: 13 additions & 13 deletions tf/test/test_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <geometry_msgs/PointStamped.h>
#include <boost/bind.hpp>
#include <boost/bind/bind.hpp>
#include <boost/scoped_ptr.hpp>

#include "ros/ros.h"
Expand Down Expand Up @@ -72,7 +72,7 @@ TEST(MessageFilter, noTransforms)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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();
Expand All @@ -87,7 +87,7 @@ TEST(MessageFilter, noTransformsSameFrame)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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();
Expand All @@ -102,7 +102,7 @@ TEST(MessageFilter, preexistingTransforms)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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");
Expand All @@ -122,7 +122,7 @@ TEST(MessageFilter, postTransforms)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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();

Expand All @@ -148,8 +148,8 @@ TEST(MessageFilter, queueSize)
tf::TransformListener tf_client;
Notification n(10);
MessageFilter<geometry_msgs::PointStamped> 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();

Expand Down Expand Up @@ -179,7 +179,7 @@ TEST(MessageFilter, setTargetFrame)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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();
Expand All @@ -201,7 +201,7 @@ TEST(MessageFilter, multipleTargetFrames)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> filter(tf_client, "", 1);
filter.registerCallback(boost::bind(&Notification::notify, &n, _1));
filter.registerCallback(boost::bind(&Notification::notify, &n, boost::placeholders::_1));

std::vector<std::string> target_frames;
target_frames.push_back("frame1");
Expand Down Expand Up @@ -239,7 +239,7 @@ TEST(MessageFilter, tolerance)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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();
Expand Down Expand Up @@ -276,7 +276,7 @@ TEST(MessageFilter, maxRate)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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");
Expand Down Expand Up @@ -313,7 +313,7 @@ TEST(MessageFilter, outTheBackFailure)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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");
Expand All @@ -335,7 +335,7 @@ TEST(MessageFilter, emptyFrameIDFailure)
tf::TransformListener tf_client;
Notification n(1);
MessageFilter<geometry_msgs::PointStamped> 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 = "";
Expand Down

0 comments on commit e91a32a

Please sign in to comment.