Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 20 additions & 16 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,33 +1,37 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(message_filters)

if(NOT WIN32)
set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Wextra")
endif()

find_package(catkin REQUIRED COMPONENTS roscpp rosconsole)
catkin_package(
INCLUDE_DIRS include
LIBRARIES message_filters
CATKIN_DEPENDS roscpp rosconsole
)
catkin_python_setup()
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

find_package(Boost REQUIRED COMPONENTS signals thread)
set(Boost_USE_STATIC_LIBS ON)
find_package(Boost REQUIRED)

include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
link_directories(${catkin_LIBRARY_DIRS})
include_directories(include
${rclcpp_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)

add_library(${PROJECT_NAME} src/connection.cpp)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
target_link_libraries(${PROJECT_NAME}
${rclcpp_LIBRARIES}
)

ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_package()

install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
DESTINATION include/${PROJECT_NAME}
FILES_MATCHING PATTERN "*.h")

if(CATKIN_ENABLE_TESTING)
Expand Down
4 changes: 2 additions & 2 deletions include/message_filters/connection.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ namespace message_filters
class MESSAGE_FILTERS_DECL Connection
{
public:
typedef boost::function<void(void)> VoidDisconnectFunction;
typedef boost::function<void(const Connection&)> WithConnectionDisconnectFunction;
typedef std::function<void(void)> VoidDisconnectFunction;
typedef std::function<void(const Connection&)> WithConnectionDisconnectFunction;
Connection() {}
Connection(const VoidDisconnectFunction& func);
Connection(const WithConnectionDisconnectFunction& func, boost::signals2::connection conn);
Expand Down
2 changes: 0 additions & 2 deletions include/message_filters/macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,6 @@
#ifndef MESSAGE_FILTERS_MACROS_H_
#define MESSAGE_FILTERS_MACROS_H_

#include <ros/macros.h> // for the DECL's

// Import/export for windows dll's and visibility for gcc shared libraries.

#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
Expand Down
18 changes: 8 additions & 10 deletions include/message_filters/signal1.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#include <boost/noncopyable.hpp>

#include "connection.h"

#include <ros/message_event.h>
#include <ros/parameter_adapter.h>

#include <boost/bind.hpp>
#include <boost/thread/mutex.hpp>
Expand All @@ -54,26 +54,24 @@ class CallbackHelper1

virtual void call(const ros::MessageEvent<M const>& event, bool nonconst_need_copy) = 0;

typedef boost::shared_ptr<CallbackHelper1<M> > Ptr;
typedef std::shared_ptr<CallbackHelper1<M> > Ptr;
};

template<typename P, typename M>
class CallbackHelper1T : public CallbackHelper1<M>
{
public:
typedef ros::ParameterAdapter<P> Adapter;
typedef boost::function<void(typename Adapter::Parameter)> Callback;
typedef typename Adapter::Event Event;
typedef std::function<void(const std::shared_ptr<M const>& msg)> Callback;

CallbackHelper1T(const Callback& cb)
: callback_(cb)
: callback_(cb)
{
}

virtual void call(const ros::MessageEvent<M const>& event, bool nonconst_force_copy)
{
Event my_event(event, nonconst_force_copy || event.nonConstWillCopy());
callback_(Adapter::getParameter(my_event));
// TODO: validate
callback_(event.getMessage());
}

private:
Expand All @@ -83,12 +81,12 @@ class CallbackHelper1T : public CallbackHelper1<M>
template<class M>
class Signal1
{
typedef boost::shared_ptr<CallbackHelper1<M> > CallbackHelper1Ptr;
typedef std::shared_ptr<CallbackHelper1<M> > CallbackHelper1Ptr;
typedef std::vector<CallbackHelper1Ptr> V_CallbackHelper1;

public:
template<typename P>
CallbackHelper1Ptr addCallback(const boost::function<void(P)>& callback)
CallbackHelper1Ptr addCallback(const std::function<void(P)>& callback)
{
CallbackHelper1T<P, M>* helper = new CallbackHelper1T<P, M>(callback);

Expand Down
21 changes: 10 additions & 11 deletions include/message_filters/simple_filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#include "connection.h"
#include "signal1.h"
#include <ros/message_event.h>
#include <ros/subscription_callback_helper.h>

#include <boost/bind.hpp>

Expand All @@ -60,10 +59,10 @@ template<class M>
class SimpleFilter : public boost::noncopyable
{
public:
typedef boost::shared_ptr<M const> MConstPtr;
typedef boost::function<void(const MConstPtr&)> Callback;
typedef std::shared_ptr<M const> MConstPtr;
typedef std::function<void(const MConstPtr&)> Callback;
typedef ros::MessageEvent<M const> EventType;
typedef boost::function<void(const EventType&)> EventCallback;
typedef std::function<void(const EventType&)> EventCallback;

/**
* \brief Register a callback to be called when this filter has passed
Expand All @@ -73,17 +72,17 @@ class SimpleFilter : public boost::noncopyable
Connection registerCallback(const C& callback)
{
typename CallbackHelper1<M>::Ptr helper = signal_.addCallback(Callback(callback));
return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
return Connection(std::bind(&Signal::removeCallback, &signal_, helper));
}

/**
* \brief Register a callback to be called when this filter has passed
* \param callback The callback to call
*/
template<typename P>
Connection registerCallback(const boost::function<void(P)>& callback)
Connection registerCallback(const std::function<void(P)>& callback)
{
return Connection(boost::bind(&Signal::removeCallback, &signal_, signal_.addCallback(callback)));
return Connection(std::bind(&Signal::removeCallback, &signal_, signal_.addCallback(callback)));
}

/**
Expand All @@ -93,8 +92,8 @@ class SimpleFilter : public boost::noncopyable
template<typename P>
Connection registerCallback(void(*callback)(P))
{
typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(boost::bind(callback, _1));
return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(std::bind(callback, std::placeholders::_1));
return Connection(std::bind(&Signal::removeCallback, &signal_, helper));
}

/**
Expand All @@ -104,8 +103,8 @@ class SimpleFilter : public boost::noncopyable
template<typename T, typename P>
Connection registerCallback(void(T::*callback)(P), T* t)
{
typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(boost::bind(callback, t, _1));
return Connection(boost::bind(&Signal::removeCallback, &signal_, helper));
typename CallbackHelper1<M>::Ptr helper = signal_.template addCallback<P>(std::bind(callback, t, std::placeholders::_1));
return Connection(std::bind(&Signal::removeCallback, &signal_, helper));
}

/**
Expand Down
52 changes: 30 additions & 22 deletions include/message_filters/subscriber.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,10 @@
#ifndef MESSAGE_FILTERS_SUBSCRIBER_H
#define MESSAGE_FILTERS_SUBSCRIBER_H

#include <ros/ros.h>
#include <utility>

#include <rclcpp/node.hpp>
#include <rclcpp/subscription.hpp>

#include <boost/thread/mutex.hpp>

Expand All @@ -60,7 +63,7 @@ class SubscriberBase
* \param transport_hints The transport hints to pass along
* \param callback_queue The callback queue to pass along
*/
virtual 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) = 0;
virtual void subscribe(rclcpp::Node::SharedPtr& nh, const std::string& topic, uint32_t queue_size) = 0;
/**
* \brief Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
*/
Expand All @@ -70,7 +73,7 @@ class SubscriberBase
*/
virtual void unsubscribe() = 0;
};
typedef boost::shared_ptr<SubscriberBase> SubscriberBasePtr;
typedef std::shared_ptr<SubscriberBase> SubscriberBasePtr;

/**
* \brief ROS subscription filter.
Expand All @@ -79,7 +82,7 @@ typedef boost::shared_ptr<SubscriberBase> SubscriberBasePtr;
* filters which have connected to it.
*
* When this object is destroyed it will unsubscribe from the ROS subscription.
*
*
* The Subscriber object is templated on the type of message being subscribed to.
*
* \section connections CONNECTIONS
Expand All @@ -90,12 +93,13 @@ typedef boost::shared_ptr<SubscriberBase> SubscriberBasePtr;
\verbatim
void callback(const boost::shared_ptr<M const>&);
\endverbatim
*/
*/
template<class M>
class Subscriber : public SubscriberBase, public SimpleFilter<M>
{
public:
typedef boost::shared_ptr<M const> MConstPtr;
typedef boost::shared_ptr<M const> BoostMConstPtr;
typedef std::shared_ptr<M> MConstPtr;
typedef ros::MessageEvent<M const> EventType;

/**
Expand All @@ -109,9 +113,9 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M>
* \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)
Subscriber(rclcpp::Node::SharedPtr& nh, const std::string& topic, uint32_t queue_size)
{
subscribe(nh, topic, queue_size, transport_hints, callback_queue);
subscribe(nh, topic, queue_size);
}

/**
Expand All @@ -137,16 +141,17 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M>
* \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)
void subscribe(rclcpp::Node::SharedPtr& nh, const std::string& topic, uint32_t queue_size)
{
unsubscribe();

if (!topic.empty())
{
ops_.template initByFullCallbackType<const EventType&>(topic, queue_size, boost::bind(&Subscriber<M>::cb, this, _1));
ops_.callback_queue = callback_queue;
ops_.transport_hints = transport_hints;
sub_ = nh.subscribe(ops_);
topic_ = topic;
// TODO: why is this multi-line version needed?
auto stdFxn = std::bind(&Subscriber<M>::cb, this, std::placeholders::_1);
std::function<void(const std::shared_ptr<M>)> stdFxnPtr = stdFxn;
sub_ = nh->create_subscription<M>(topic_, stdFxnPtr, rmw_qos_profile_default);
nh_ = nh;
}
}
Expand All @@ -158,9 +163,12 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M>
{
unsubscribe();

if (!ops_.topic.empty())
if (!topic_.empty())
{
sub_ = nh_.subscribe(ops_);
// TODO: why is this multi-line version needed?
auto stdFxn = std::bind(&Subscriber<M>::cb, this, std::placeholders::_1);
std::function<void(const std::shared_ptr<M>)> stdFxnPtr = stdFxn;
sub_ = nh_->create_subscription<M>(topic_, stdFxnPtr, rmw_qos_profile_default);
}
}

Expand All @@ -169,18 +177,18 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M>
*/
void unsubscribe()
{
sub_.shutdown();
// TODO: No idea how to do this in ROS2???
}

std::string getTopic() const
{
return ops_.topic;
return sub_->get_topic_name();
}

/**
* \brief Returns the internal ros::Subscriber object
*/
const ros::Subscriber& getSubscriber() const { return sub_; }
const std::shared_ptr<rclcpp::Subscription<M>> getSubscriber() const { return sub_; }

/**
* \brief Does nothing. Provided so that Subscriber may be used in a message_filters::Chain
Expand All @@ -201,14 +209,14 @@ class Subscriber : public SubscriberBase, public SimpleFilter<M>

private:

void cb(const EventType& e)
void cb(const MConstPtr& e)
{
this->signalMessage(e);
}

ros::Subscriber sub_;
ros::SubscribeOptions ops_;
ros::NodeHandle nh_;
std::string topic_;
std::shared_ptr<rclcpp::Subscription<M>> sub_;
rclcpp::Node::SharedPtr nh_;
};

}
Expand Down
17 changes: 6 additions & 11 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
<package>
<?xml version="1.0"?>
<package format="2">
<name>message_filters</name>
<version>1.14.2</version>
<description>
Expand All @@ -12,18 +13,12 @@
<author>Josh Faust</author>
<author>Vijay Pradeep</author>

<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>boost</build_depend>
<build_depend>rosconsole</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rostest</build_depend>
<build_depend>rosunit</build_depend>

<run_depend>rosconsole</run_depend>
<run_depend>roscpp</run_depend>
<build_depend>rclcpp</build_depend>
<exec_depend>rclcpp</exec_depend>

<export>
<rosdoc config="rosdoc.yaml"/>
<build_type>ament_cmake</build_type>
</export>
</package>