Template Class MessageFilter

Nested Relationships

Nested Types

Inheritance Relationships

Base Types

Class Documentation

template<class M, class BufferT = tf2_ros::Buffer>
class MessageFilter : public tf2_ros::MessageFilterBase, public message_filters::SimpleFilter<M>

Follows the patterns set by the message_filters package to implement a filter which only passes messages through once there is transform data available.

The callbacks used in this class are of the same form as those used by rclcpp’s message callbacks.

MessageFilter is templated on a message type.

Example Usage

If you want to hook a MessageFilter into a ROS topic:

  message_filters::Subscriber<MessageType> sub(node_, "topic", 10);
  tf::MessageFilter<MessageType> tf_filter(sub, tf_listener_, "/map", 10);
  tf_filter.registerCallback(&MyClass::myCallback, this);

Public Types

using MConstPtr = std::shared_ptr<M const>
typedef message_filters::MessageEvent<M const> MEvent

Public Functions

template<typename TimeRepT = int64_t, typename TimeT = std::nano>
inline MessageFilter(BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::Node::SharedPtr &node, std::chrono::duration<TimeRepT, TimeT> buffer_timeout = std::chrono::duration<TimeRepT, TimeT>::max())

Constructor.

Parameters:
  • buffer – The buffer this filter should use

  • target_frame – The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.

  • queue_size – The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).

  • node – The ros2 node to use for logging and clock operations

  • buffer_timeout – The timeout duration after requesting transforms from the buffer.

template<typename TimeRepT = int64_t, typename TimeT = std::nano>
inline MessageFilter(BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &node_logging, const rclcpp::node_interfaces::NodeClockInterface::SharedPtr &node_clock, std::chrono::duration<TimeRepT, TimeT> buffer_timeout = std::chrono::duration<TimeRepT, TimeT>::max())

Constructor.

Parameters:
  • buffer – The buffer this filter should use

  • target_frame – The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.

  • queue_size – The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).

  • node_logging – The logging interface to use for any log messages

  • node_clock – The clock interface to use to get the node clock

  • buffer_timeout – The timeout duration after requesting transforms from the buffer.

template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
inline MessageFilter(F &f, BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::Node::SharedPtr &node, std::chrono::duration<TimeRepT, TimeT> buffer_timeout = std::chrono::duration<TimeRepT, TimeT>::max())

Constructor.

Parameters:
  • f – The filter to connect this filter’s input to. Often will be a message_filters::Subscriber.

  • buffer – The buffer this filter should use

  • target_frame – The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.

  • queue_size – The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).

  • node – The ros2 node to use for logging and clock operations

  • buffer_timeout – The timeout duration after requesting transforms from the buffer.

template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
inline MessageFilter(F &f, BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &node_logging, const rclcpp::node_interfaces::NodeClockInterface::SharedPtr &node_clock, std::chrono::duration<TimeRepT, TimeT> buffer_timeout = std::chrono::duration<TimeRepT, TimeT>::max())

Constructor.

Parameters:
  • f – The filter to connect this filter’s input to. Often will be a message_filters::Subscriber.

  • buffer – The buffer this filter should use

  • target_frame – The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.

  • queue_size – The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).

  • node_logging – The logging interface to use for any log messages

  • node_clock – The clock interface to use to get the node clock

  • buffer_timeout – The timeout duration after requesting transforms from the buffer.

template<class F>
inline void connectInput(F &f)

Connect this filter’s input to another filter’s output. If this filter is already connected, disconnects first.

inline ~MessageFilter()

Destructor.

inline virtual void setTargetFrame(const std::string &target_frame)

Set the frame you need to be able to transform to before getting a message callback.

inline virtual void setTargetFrames(const V_string &target_frames)

Set the frames you need to be able to transform to before getting a message callback.

inline std::string getTargetFramesString()

Get the target frames as a string for debugging.

inline virtual void setTolerance(const rclcpp::Duration &tolerance)

Set the required tolerance for the notifier to return true.

inline virtual void clear()

Clear any messages currently in the queue.

inline void add(const MEvent &evt)
inline void add(const MConstPtr &message)

Manually add a message into this filter.

Note

If the message (or any other messages in the queue) are immediately transformable this will immediately call through to the output callback, possibly multiple times

inline virtual void setQueueSize(uint32_t new_queue_size)

Register a callback to be called when a message is about to be dropped.

Parameters:

callback – The callback to call

inline virtual uint32_t getQueueSize()