|
From: <jfa...@us...> - 2009-07-06 22:29:09
|
Revision: 18349
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18349&view=rev
Author: jfaustwg
Date: 2009-07-06 22:29:05 +0000 (Mon, 06 Jul 2009)
Log Message:
-----------
Wrap boost::signals::connection with our own message_filters::Connection class for two reasons:
1) boost::signals is not thread-safe, so calling disconnect() directly on the connection is not safe in our case. boost::signals2 is thread-safe, but did not come out until 1.39
2) Niceness of not exposing the boost::signals API to users
Modified Paths:
--------------
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/dense_laser_msg_filter.h
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/joint_pv_msg_filter.h
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/laser_scan_tagger.h
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp
pkg/trunk/sandbox/message_filters/CMakeLists.txt
pkg/trunk/sandbox/message_filters/include/message_filters/cache.h
pkg/trunk/sandbox/message_filters/include/message_filters/subscriber.h
pkg/trunk/sandbox/message_filters/include/message_filters/time_synchronizer.h
pkg/trunk/sandbox/message_filters/manifest.xml
pkg/trunk/sandbox/message_filters/test/CMakeLists.txt
pkg/trunk/stacks/geometry/tf/include/tf/message_filter.h
pkg/trunk/stacks/geometry/tf/manifest.xml
Added Paths:
-----------
pkg/trunk/sandbox/message_filters/include/message_filters/connection.h
pkg/trunk/sandbox/message_filters/src/connection.cpp
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/dense_laser_msg_filter.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/dense_laser_msg_filter.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/dense_laser_msg_filter.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -42,6 +42,7 @@
#include "dense_laser_assembler/joint_pv_msg_filter.h"
#include "dense_laser_assembler/laser_scan_tagger.h"
#include "message_filters/cache.h"
+#include "message_filters/connection.h"
// Messages
@@ -137,7 +138,7 @@
* \brief Used to connect this MessageFilter to a callback
* \param callback Function to be called whenever a new TaggedLaserScan message is available
*/
- boost::signals::connection connect(const Callback& callback) ;
+ message_filters::Connection connect(const Callback& callback) ;
//! \brief Not yet implemented
void processLaserScan(const sensor_msgs::LaserScanConstPtr& msg) ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/joint_pv_msg_filter.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/joint_pv_msg_filter.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/joint_pv_msg_filter.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -44,6 +44,8 @@
#include <boost/thread.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/signals.hpp>
+#include <boost/bind.hpp>
+#include <message_filters/connection.h>
// Messages
#include "dense_laser_assembler/JointPVArray.h"
@@ -100,10 +102,10 @@
* \brief Called by user wants they want to connect this MessageFilter to their own code
* \param callback Function to be called whenever a JointPVArray message is available
*/
- boost::signals::connection connect(const Callback& callback)
+ message_filters::Connection connect(const Callback& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(callback);
+ return message_filters::Connection(boost::bind(&JointPVMsgFilter::disconnect, this, _1), signal_.connect(callback));
}
/**
@@ -154,11 +156,17 @@
}
protected:
+ void disconnect(const message_filters::Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
boost::mutex joint_mapping_mutex_ ;
std::vector<std::string> joint_names_ ;
// Filter Connection Stuff
- boost::signals::connection incoming_connection_;
+ message_filters::Connection incoming_connection_;
Signal signal_;
boost::mutex signal_mutex_;
} ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/laser_scan_tagger.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/laser_scan_tagger.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/include/dense_laser_assembler/laser_scan_tagger.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -139,10 +139,10 @@
* \brief Connect this message filter's output to some callback
* \param callback Function to call after we've tagged a LaserScan
*/
- boost::signals::connection connect(const Callback& callback)
+ message_filters::Connection connect(const Callback& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(callback);
+ return message_filters::Connection(boost::bind(&LaserScanTagger::disconnect, this, _1), signal_.connect(callback));
}
/**
@@ -213,14 +213,20 @@
}
private:
+ void disconnect(const message_filters::Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
std::deque<sensor_msgs::LaserScanConstPtr> queue_ ; //!< Incoming queue of laser scans
boost::mutex queue_mutex_ ; //!< Mutex for laser scan queue
unsigned int max_queue_size_ ; //!< Max # of laser scans to queue up for processing
message_filters::Cache<T>* tag_cache_ ; //!< Cache of the tags that we need to merge with laser data
Signal signal_;
- boost::signals::connection incoming_laser_scan_connection_;
- boost::signals::connection incoming_tag_connection_;
+ message_filters::Connection incoming_laser_scan_connection_;
+ message_filters::Connection incoming_tag_connection_;
boost::mutex signal_mutex_;
} ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/joint_extractor_display.cpp 2009-07-06 22:29:05 UTC (rev 18349)
@@ -85,7 +85,7 @@
JointPVMsgFilter joint_extractor(joint_names) ;
//JointPVDiagMsgFilter joint_extractor(diagnostic, joint_names) ;
- boost::signals::connection con = joint_extractor.connect( boost::bind(&display_joints, joint_names, _1) ) ;
+ message_filters::Connection con = joint_extractor.connect( boost::bind(&display_joints, joint_names, _1) ) ;
ros::Subscriber sub = nh.subscribe("mechanism_state", 1, &JointPVMsgFilter::processMechState, &joint_extractor) ;
Modified: pkg/trunk/sandbox/message_filters/CMakeLists.txt
===================================================================
--- pkg/trunk/sandbox/message_filters/CMakeLists.txt 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/CMakeLists.txt 2009-07-06 22:29:05 UTC (rev 18349)
@@ -2,7 +2,14 @@
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
rospack(message_filters)
+include_directories(include/message_filters)
+
+rospack_add_boost_directories()
+rospack_add_library(message_filters src/connection.cpp)
+rospack_link_boost(message_filters thread signals)
+
#rospack_add_executable(filter_example src/filter_example.cpp)
+#target_link_libraries(filter_example message_filters)
set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
Modified: pkg/trunk/sandbox/message_filters/include/message_filters/cache.h
===================================================================
--- pkg/trunk/sandbox/message_filters/include/message_filters/cache.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/include/message_filters/cache.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -46,6 +46,8 @@
#include <boost/noncopyable.hpp>
#include "ros/time.h"
+#include "connection.h"
+
namespace message_filters
{
@@ -104,10 +106,10 @@
cache_size_ = cache_size ;
}
- boost::signals::connection connect(const Callback& callback)
+ Connection connect(const Callback& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(callback);
+ return Connection(boost::bind(&Cache::disconnect, this, _1), signal_.connect(callback));
}
/**
@@ -252,11 +254,17 @@
}
private:
+ void disconnect(const Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
boost::mutex cache_lock_ ; //!< Lock for cache_
std::deque<MConstPtr > cache_ ; //!< Cache for the messages
unsigned int cache_size_ ; //!< Maximum number of elements allowed in the cache.
- boost::signals::connection incoming_connection_;
+ Connection incoming_connection_;
Signal signal_;
boost::mutex signal_mutex_;
};
Added: pkg/trunk/sandbox/message_filters/include/message_filters/connection.h
===================================================================
--- pkg/trunk/sandbox/message_filters/include/message_filters/connection.h (rev 0)
+++ pkg/trunk/sandbox/message_filters/include/message_filters/connection.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -0,0 +1,76 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2009, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#ifndef MESSAGE_FILTERS_CONNECTION_H
+#define MESSAGE_FILTERS_CONNECTION_H
+
+#include <boost/thread/mutex.hpp>
+#include <boost/function.hpp>
+#include <boost/signals.hpp>
+
+namespace message_filters
+{
+
+class Connection
+{
+public:
+ typedef boost::function<void(const Connection&)> DisconnectFunction;
+
+ Connection();
+ Connection(const DisconnectFunction& func, boost::signals::connection conn);
+ Connection(const Connection& rhs);
+ Connection& operator=(const Connection& rhs);
+
+ void disconnect();
+
+ boost::signals::connection getBoostConnection() const;
+
+private:
+ class Impl
+ {
+ public:
+ Impl();
+ ~Impl();
+
+ DisconnectFunction disconnect_;
+ boost::signals::connection connection_;
+ };
+ typedef boost::shared_ptr<Impl> ImplPtr;
+
+ ImplPtr impl_;
+};
+
+}
+
+#endif // MESSAGE_FILTERS_CONNECTION_H
Modified: pkg/trunk/sandbox/message_filters/include/message_filters/subscriber.h
===================================================================
--- pkg/trunk/sandbox/message_filters/include/message_filters/subscriber.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/include/message_filters/subscriber.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -41,9 +41,17 @@
#include <boost/thread/mutex.hpp>
#include <boost/noncopyable.hpp>
+#include "connection.h"
+
namespace message_filters
{
+/**
+ * \brief ROS subscription filter.
+ *
+ * This class acts as a highest-level filter, simply passing messages from a ROS subscription through to the
+ * filters which have connected to it.
+ */
template<class M>
class Subscriber : public boost::noncopyable
{
@@ -52,22 +60,49 @@
typedef boost::function<void(const MConstPtr&)> Callback;
typedef boost::signal<void(const MConstPtr&)> Signal;
+ /**
+ * \brief Constructor
+ *
+ * See the ros::NodeHandle::subscribe() variants for more information on the parameters
+ *
+ * \param nh The ros::NodeHandle to use to subscribe.
+ * \param topic The topic to subscribe to.
+ * \param queue_size The subscription queue size
+ * \param transport_hints The transport hints to pass along
+ * \param callback_queue The callback queue to pass along
+ */
Subscriber(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0)
{
subscribe(nh, topic, queue_size, transport_hints, callback_queue);
}
+ /**
+ * \brief Empty constructor, use subscribe() to subscribe to a topic
+ */
Subscriber()
{
}
~Subscriber()
{
- sub_.shutdown();
+ unsubscribe();
}
+ /**
+ * \brief Subscribe to a topic.
+ *
+ * If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
+ *
+ * \param nh The ros::NodeHandle to use to subscribe.
+ * \param topic The topic to subscribe to.
+ * \param queue_size The subscription queue size
+ * \param transport_hints The transport hints to pass along
+ * \param callback_queue The callback queue to pass along
+ */
void subscribe(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0)
{
+ unsubscribe();
+
ros::SubscribeOptions ops;
ops.init<M>(topic, queue_size, boost::bind(&Subscriber<M>::cb, this, _1));
ops.callback_queue = callback_queue;
@@ -80,13 +115,25 @@
sub_.shutdown();
}
- boost::signals::connection connect(const Callback& callback)
+ /**
+ * \brief Connect a callback to this filter. That callback will be called whenever new data arrives.
+ *
+ * \param callback A function of the same form as the message callbacks used in roscpp
+ * \return A connection object that allows you to disconnect from this
+ */
+ Connection connect(const Callback& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(callback);
+ return Connection(boost::bind(&Subscriber::disconnect, this, _1), signal_.connect(callback));
}
private:
+ void disconnect(const Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
void cb(const MConstPtr& m)
{
boost::mutex::scoped_lock lock(signal_mutex_);
Modified: pkg/trunk/sandbox/message_filters/include/message_filters/time_synchronizer.h
===================================================================
--- pkg/trunk/sandbox/message_filters/include/message_filters/time_synchronizer.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/include/message_filters/time_synchronizer.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -46,6 +46,8 @@
#include <roslib/Header.h>
+#include "connection.h"
+
#define TIME_SYNCHRONIZER_MAX_MESSAGES 9
namespace message_filters
@@ -64,9 +66,9 @@
public:
typedef boost::shared_ptr<M const> MConstPtr;
typedef boost::function<void(const MConstPtr&)> Callback;
- boost::signals::connection connect(const Callback& cb)
+ Connection connect(const Callback& cb)
{
- return boost::signals::connection();
+ return Connection();
}
};
@@ -228,10 +230,10 @@
}
template<class C>
- boost::signals::connection connect(const C& callback)
+ Connection connect(const C& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8, _9));
+ return Connection(boost::bind(&TimeSynchronizer::disconnect, this, _1), signal_.connect(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8, _9)));
}
void add0(const M0ConstPtr& msg)
@@ -492,6 +494,12 @@
}
}
+ void disconnect(const Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
uint32_t queue_size_;
typedef std::map<ros::Time, Tuple> M_TimeToTuple;
@@ -502,7 +510,7 @@
boost::mutex signal_mutex_;
ros::Time last_signal_time_;
- boost::signals::connection input_connections_[TIME_SYNCHRONIZER_MAX_MESSAGES];
+ Connection input_connections_[TIME_SYNCHRONIZER_MAX_MESSAGES];
uint32_t real_type_count_;
};
Modified: pkg/trunk/sandbox/message_filters/manifest.xml
===================================================================
--- pkg/trunk/sandbox/message_filters/manifest.xml 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/manifest.xml 2009-07-06 22:29:05 UTC (rev 18349)
@@ -8,7 +8,7 @@
<depend package="robot_msgs" />
<depend package="sensor_msgs" />
<export>
- <cpp cflags="-I${prefix}/include" />
+ <cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lmessage_filters `rosboost-cfg --lflags thread,signals`" />
</export>
<url>http://pr.willowgarage.com/wiki/topic_synchronizer</url>
</package>
Added: pkg/trunk/sandbox/message_filters/src/connection.cpp
===================================================================
--- pkg/trunk/sandbox/message_filters/src/connection.cpp (rev 0)
+++ pkg/trunk/sandbox/message_filters/src/connection.cpp 2009-07-06 22:29:05 UTC (rev 18349)
@@ -0,0 +1,89 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2009, Willow Garage, Inc.
+* All rights reserved.
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* * Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* * Redistributions in binary form must reproduce the above
+* copyright notice, this list of conditions and the following
+* disclaimer in the documentation and/or other materials provided
+* with the distribution.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may be used to endorse or promote products derived
+* from this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+* POSSIBILITY OF SUCH DAMAGE.
+*********************************************************************/
+
+#include "connection.h"
+
+namespace message_filters
+{
+
+Connection::Impl::Impl()
+{
+}
+
+Connection::Impl::~Impl()
+{
+}
+
+Connection::Connection()
+{
+}
+
+Connection::Connection(const Connection& rhs)
+{
+ impl_ = rhs.impl_;
+}
+
+Connection::Connection(const DisconnectFunction& func, boost::signals::connection conn)
+: impl_(new Impl)
+{
+ impl_->disconnect_ = func;
+ impl_->connection_ = conn;
+}
+
+Connection& Connection::operator=(const Connection& rhs)
+{
+ impl_ = rhs.impl_;
+
+ return *this;
+}
+
+void Connection::disconnect()
+{
+ if (impl_)
+ {
+ impl_->disconnect_(*this);
+ }
+}
+
+boost::signals::connection Connection::getBoostConnection() const
+{
+ if (impl_)
+ {
+ return impl_->connection_;
+ }
+
+ return boost::signals::connection();
+}
+
+}
Modified: pkg/trunk/sandbox/message_filters/test/CMakeLists.txt
===================================================================
--- pkg/trunk/sandbox/message_filters/test/CMakeLists.txt 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/sandbox/message_filters/test/CMakeLists.txt 2009-07-06 22:29:05 UTC (rev 18349)
@@ -2,4 +2,7 @@
# ********** Tests **********
rospack_add_gtest(test/msg_cache_unittest msg_cache_unittest.cpp)
+target_link_libraries(test/msg_cache_unittest message_filters)
+
rospack_add_gtest(test/time_synchronizer_unittest time_synchronizer_unittest.cpp)
+target_link_libraries(test/time_synchronizer_unittest message_filters)
Modified: pkg/trunk/stacks/geometry/tf/include/tf/message_filter.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/message_filter.h 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/stacks/geometry/tf/include/tf/message_filter.h 2009-07-06 22:29:05 UTC (rev 18349)
@@ -49,6 +49,8 @@
#include <ros/callback_queue.h>
+#include <message_filters/connection.h>
+
#define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: "fmt, getTargetFramesString().c_str(), __VA_ARGS__)
@@ -101,10 +103,7 @@
template<class F>
void subscribeTo(F& f)
{
- if (message_connection_.connected())
- {
- message_connection_.disconnect();
- }
+ message_connection_.disconnect();
message_connection_ = f.connect(boost::bind(&MessageFilter::incomingMessage, this, _1));
}
@@ -208,10 +207,10 @@
++incoming_message_count_;
}
- boost::signals::connection connect(const Callback& callback)
+ message_filters::Connection connect(const Callback& callback)
{
boost::mutex::scoped_lock lock(signal_mutex_);
- return signal_.connect(callback);
+ return message_filters::Connection(boost::bind(&MessageFilter::disconnect, this, _1), signal_.connect(callback));
}
private:
@@ -452,6 +451,12 @@
}
}
+ void disconnect(const message_filters::Connection& c)
+ {
+ boost::mutex::scoped_lock lock(signal_mutex_);
+ signal_.disconnect(c.getBoostConnection());
+ }
+
Transformer& tf_; ///< The Transformer used to determine if transformation data is available
ros::NodeHandle nh_; ///< The node used to subscribe to the topic
ros::Duration min_rate_;
@@ -489,7 +494,7 @@
ros::Duration time_tolerance_; ///< Provide additional tolerance on time for messages which are stamped but can have associated duration
boost::signals::connection tf_connection_;
- boost::signals::connection message_connection_;
+ message_filters::Connection message_connection_;
};
} // namespace tf
Modified: pkg/trunk/stacks/geometry/tf/manifest.xml
===================================================================
--- pkg/trunk/stacks/geometry/tf/manifest.xml 2009-07-06 22:24:45 UTC (rev 18348)
+++ pkg/trunk/stacks/geometry/tf/manifest.xml 2009-07-06 22:29:05 UTC (rev 18349)
@@ -15,6 +15,7 @@
<depend package="rospy"/>
<depend package="rostest"/>
<depend package="roswtf"/>
+ <depend package="message_filters"/>
<export>
<cpp cflags="-I${prefix}/include -I${prefix}/msg/cpp -I${prefix}/srv/cpp `rosboost-cfg --cflags`" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -ltf `rosboost-cfg --lflags thread`"/>
<roswtf plugin="tf.tfwtf" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|