tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
Classes | Public Types | Public Member Functions | List of all members
tf2_ros::MessageFilter< M, BufferT > Class Template Reference

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

#include <message_filter.h>

Inheritance diagram for tf2_ros::MessageFilter< M, BufferT >:
Inheritance graph
[legend]
Collaboration diagram for tf2_ros::MessageFilter< M, BufferT >:
Collaboration graph
[legend]

Public Types

using MConstPtr = std::shared_ptr< M const >
 
typedef message_filters::MessageEvent< M const > MEvent
 
- Public Types inherited from tf2_ros::MessageFilterBase
typedef std::vector< std::stringV_string
 

Public Member Functions

template<typename TimeRepT = int64_t, typename TimeT = std::nano>
 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. More...
 
template<typename TimeRepT = int64_t, typename TimeT = std::nano>
 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. More...
 
template<class F , typename TimeRepT = int64_t, typename TimeT = std::nano>
 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. More...
 
template<class F , typename TimeRepT = int64_t, typename TimeT = std::nano>
 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. More...
 
template<class F >
void connectInput (F &f)
 Connect this filter's input to another filter's output. If this filter is already connected, disconnects first. More...
 
 ~MessageFilter ()
 Destructor. More...
 
void setTargetFrame (const std::string &target_frame)
 Set the frame you need to be able to transform to before getting a message callback. More...
 
void setTargetFrames (const V_string &target_frames)
 Set the frames you need to be able to transform to before getting a message callback. More...
 
std::string getTargetFramesString ()
 Get the target frames as a string for debugging. More...
 
void setTolerance (const rclcpp::Duration &tolerance)
 Set the required tolerance for the notifier to return true. More...
 
void clear ()
 Clear any messages currently in the queue. More...
 
void add (const MEvent &evt)
 
void add (const MConstPtr &message)
 Manually add a message into this filter. More...
 
virtual void setQueueSize (uint32_t new_queue_size)
 Register a callback to be called when a message is about to be dropped. More...
 
virtual uint32_t getQueueSize ()
 
- Public Member Functions inherited from tf2_ros::MessageFilterBase
virtual ~MessageFilterBase ()
 
virtual void setTargetFrames (const V_string &target_frames)=0
 

Detailed Description

template<class M, class BufferT = tf2_ros::Buffer>
class tf2_ros::MessageFilter< M, BufferT >

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);

Member Typedef Documentation

◆ MConstPtr

template<class M , class BufferT = tf2_ros::Buffer>
using tf2_ros::MessageFilter< M, BufferT >::MConstPtr = std::shared_ptr<M const>

◆ MEvent

template<class M , class BufferT = tf2_ros::Buffer>
typedef message_filters::MessageEvent<M const> tf2_ros::MessageFilter< M, BufferT >::MEvent

Constructor & Destructor Documentation

◆ MessageFilter() [1/4]

template<class M , class BufferT = tf2_ros::Buffer>
template<typename TimeRepT = int64_t, typename TimeT = std::nano>
tf2_ros::MessageFilter< M, BufferT >::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() 
)
inline

Constructor.

Parameters
bufferThe buffer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
nodeThe ros2 node to use for logging and clock operations
buffer_timeoutThe timeout duration after requesting transforms from the buffer.

◆ MessageFilter() [2/4]

template<class M , class BufferT = tf2_ros::Buffer>
template<typename TimeRepT = int64_t, typename TimeT = std::nano>
tf2_ros::MessageFilter< M, BufferT >::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() 
)
inline

Constructor.

Parameters
bufferThe buffer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
node_loggingThe logging interface to use for any log messages
node_clockThe clock interface to use to get the node clock
buffer_timeoutThe timeout duration after requesting transforms from the buffer.

◆ MessageFilter() [3/4]

template<class M , class BufferT = tf2_ros::Buffer>
template<class F , typename TimeRepT = int64_t, typename TimeT = std::nano>
tf2_ros::MessageFilter< M, BufferT >::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() 
)
inline

Constructor.

Parameters
fThe filter to connect this filter's input to. Often will be a message_filters::Subscriber.
bufferThe buffer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
nodeThe ros2 node to use for logging and clock operations
buffer_timeoutThe timeout duration after requesting transforms from the buffer.

◆ MessageFilter() [4/4]

template<class M , class BufferT = tf2_ros::Buffer>
template<class F , typename TimeRepT = int64_t, typename TimeT = std::nano>
tf2_ros::MessageFilter< M, BufferT >::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() 
)
inline

Constructor.

Parameters
fThe filter to connect this filter's input to. Often will be a message_filters::Subscriber.
bufferThe buffer this filter should use
target_frameThe frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function.
queue_sizeThe number of messages to queue up before throwing away old ones. 0 means infinite (dangerous).
node_loggingThe logging interface to use for any log messages
node_clockThe clock interface to use to get the node clock
buffer_timeoutThe timeout duration after requesting transforms from the buffer.

◆ ~MessageFilter()

template<class M , class BufferT = tf2_ros::Buffer>
tf2_ros::MessageFilter< M, BufferT >::~MessageFilter ( )
inline

Destructor.

Member Function Documentation

◆ connectInput()

template<class M , class BufferT = tf2_ros::Buffer>
template<class F >
void tf2_ros::MessageFilter< M, BufferT >::connectInput ( F &  f)
inline

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

◆ setTargetFrame()

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::setTargetFrame ( const std::string target_frame)
inlinevirtual

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

Implements tf2_ros::MessageFilterBase.

◆ setTargetFrames()

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::setTargetFrames ( const V_string target_frames)
inline

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

◆ getTargetFramesString()

template<class M , class BufferT = tf2_ros::Buffer>
std::string tf2_ros::MessageFilter< M, BufferT >::getTargetFramesString ( )
inline

Get the target frames as a string for debugging.

◆ setTolerance()

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::setTolerance ( const rclcpp::Duration &  tolerance)
inlinevirtual

Set the required tolerance for the notifier to return true.

Implements tf2_ros::MessageFilterBase.

◆ clear()

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::clear ( )
inlinevirtual

Clear any messages currently in the queue.

Implements tf2_ros::MessageFilterBase.

◆ add() [1/2]

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::add ( const MEvent evt)
inline

◆ add() [2/2]

template<class M , class BufferT = tf2_ros::Buffer>
void tf2_ros::MessageFilter< M, BufferT >::add ( const MConstPtr message)
inline

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

◆ setQueueSize()

template<class M , class BufferT = tf2_ros::Buffer>
virtual void tf2_ros::MessageFilter< M, BufferT >::setQueueSize ( uint32_t  new_queue_size)
inlinevirtual

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

Parameters
callbackThe callback to call

◆ getQueueSize()

template<class M , class BufferT = tf2_ros::Buffer>
virtual uint32_t tf2_ros::MessageFilter< M, BufferT >::getQueueSize ( )
inlinevirtual

The documentation for this class was generated from the following file: