tf2_ros
master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
|
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>
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::string > | V_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 |
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.
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);
using tf2_ros::MessageFilter< M, BufferT >::MConstPtr = std::shared_ptr<M const> |
typedef message_filters::MessageEvent<M const> tf2_ros::MessageFilter< M, BufferT >::MEvent |
|
inline |
Constructor.
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. |
|
inline |
Constructor.
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. |
|
inline |
Constructor.
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. |
|
inline |
Constructor.
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. |
|
inline |
Destructor.
|
inline |
Connect this filter's input to another filter's output. If this filter is already connected, disconnects first.
|
inlinevirtual |
Set the frame you need to be able to transform to before getting a message callback.
Implements tf2_ros::MessageFilterBase.
|
inline |
Set the frames you need to be able to transform to before getting a message callback.
|
inline |
Get the target frames as a string for debugging.
|
inlinevirtual |
Set the required tolerance for the notifier to return true.
Implements tf2_ros::MessageFilterBase.
|
inlinevirtual |
Clear any messages currently in the queue.
Implements tf2_ros::MessageFilterBase.
|
inline |
|
inline |
Manually add a message into this filter.
|
inlinevirtual |
Register a callback to be called when a message is about to be dropped.
callback | The callback to call |
|
inlinevirtual |