Skip to content

Commit

Permalink
most of a patch for ros/geometry#23 but blocked by ros/ros_comm#267
Browse files Browse the repository at this point in the history
  • Loading branch information
tfoote committed Aug 3, 2013
1 parent c317a24 commit 50cf3e1
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
10 changes: 5 additions & 5 deletions tf2/include/tf2/buffer_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

#include "transform_storage.h"

#include <boost/signals.hpp>
#include <boost/signals2.hpp>

#include <string>

Expand Down Expand Up @@ -250,11 +250,11 @@ class BufferCore
* \brief Add a callback that happens when a new transform has arrived
*
* \param callback The callback, of the form void func();
* \return A boost::signals::connection object that can be used to remove this
* \return A boost::signals2::connection object that can be used to remove this
* listener
*/
boost::signals::connection _addTransformsChangedListener(boost::function<void(void)> callback);
void _removeTransformsChangedListener(boost::signals::connection c);
boost::signals2::connection _addTransformsChangedListener(boost::function<void(void)> callback);
void _removeTransformsChangedListener(boost::signals2::connection c);


/**@brief Check if a frame exists in the tree
Expand Down Expand Up @@ -355,7 +355,7 @@ class BufferCore
struct RemoveRequestByID;

// Backwards compatability for tf message_filter
typedef boost::signal<void(void)> TransformsChangedSignal;
typedef boost::signals2::signal<void(void)> TransformsChangedSignal;
/// Signal which is fired whenever new transform data has arrived, from the thread the data arrived in
TransformsChangedSignal _transforms_changed_;

Expand Down
4 changes: 2 additions & 2 deletions tf2/src/buffer_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1193,13 +1193,13 @@ void BufferCore::cancelTransformableRequest(TransformableRequestHandle handle)


// backwards compability for tf methods
boost::signals::connection BufferCore::_addTransformsChangedListener(boost::function<void(void)> callback)
boost::signals2::connection BufferCore::_addTransformsChangedListener(boost::function<void(void)> callback)
{
boost::mutex::scoped_lock lock(transformable_requests_mutex_);
return _transforms_changed_.connect(callback);
}

void BufferCore::_removeTransformsChangedListener(boost::signals::connection c)
void BufferCore::_removeTransformsChangedListener(boost::signals2::connection c)
{
boost::mutex::scoped_lock lock(transformable_requests_mutex_);
c.disconnect();
Expand Down
4 changes: 2 additions & 2 deletions tf2_ros/include/tf2_ros/message_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
#include <boost/bind.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/thread.hpp>
#include <boost/signals.hpp>
#include <boost/signals2.hpp>

#include <message_filters/connection.h>
#include <message_filters/simple_filter.h>
Expand Down Expand Up @@ -108,7 +108,7 @@ class MessageFilter : public MessageFilterBase, public message_filters::SimpleFi
typedef boost::shared_ptr<M const> MConstPtr;
typedef ros::MessageEvent<M const> MEvent;
typedef boost::function<void(const MConstPtr&, FilterFailureReason)> FailureCallback;
typedef boost::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;

// If you hit this assert your message does not have a header, or does not have the HasHeader trait defined for it
ROS_STATIC_ASSERT(ros::message_traits::HasHeader<M>::value);
Expand Down

0 comments on commit 50cf3e1

Please sign in to comment.