FKIE Message Filters
Improved filters for processing ROS messages
|
Wait for TF transformations for incoming messages. More...
#include <fkie_message_filters/tf_filter.h>
Public Types | |
using | FilterFailureCB = std::function< void(const Inputs &..., TfFilterResult)> |
Callback for failed transform queries. | |
using | Input = IO< Inputs... > |
Grouped input types. More... | |
using | Output = IO< Outputs... > |
Grouped output types. More... | |
Public Member Functions | |
TfFilter () noexcept | |
Empty constructor. More... | |
TfFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh) noexcept | |
Construct and initialize the filter. More... | |
TfFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbq) noexcept | |
Construct and initialize the filter. More... | |
TfFilter (tf2::BufferCore &bc, const ros::V_string &target_frames, uint32_t queue_size, const ros::NodeHandle &nh) noexcept | |
Construct and initialize the filter. More... | |
TfFilter (tf2::BufferCore &bc, const ros::V_string &target_frames, uint32_t queue_size, ros::CallbackQueueInterface *cbq) noexcept | |
Construct and initialize the filter. More... | |
Connection | connect_to_sink (Sink< Outputs... > &dst) noexcept |
Connect this source to a sink. More... | |
Connection | connect_to_source (Source< Inputs... > &src) noexcept |
Connect this sink to a source. More... | |
void | disconnect_from_all_sinks () noexcept |
Disconnect from all connected sinks. More... | |
void | disconnect_from_all_sources () noexcept |
Disconnect from all connected sources. More... | |
void | init (tf2::BufferCore &bc, uint32_t queue_size, const ros::NodeHandle &nh) noexcept |
Initialize the filter. More... | |
void | init (tf2::BufferCore &bc, uint32_t queue_size, ros::CallbackQueueInterface *cbq) noexcept |
Initialize the filter. More... | |
void | reset () noexcept override |
Reset filter state. More... | |
void | set_filter_failure_function (FilterFailureCB cb) |
Register callback for failed transforms. More... | |
void | set_target_frame (const std::string &target_frame) |
Choose the TF target frame. More... | |
void | set_target_frames (const ros::V_string &target_frames) |
Choose the TF target frames. More... | |
Static Public Attributes | |
static constexpr std::size_t | NUM_INPUTS = sizeof...(Inputs) |
Number of input arguments. | |
static constexpr std::size_t | NUM_OUTPUTS |
Number of output arguments. | |
Protected Member Functions | |
void | receive (const Inputs &... in) override |
Process incoming data. More... | |
void | send (const Outputs &... out) |
Pass data to all connected sinks. More... | |
Wait for TF transformations for incoming messages.
This filter is intended to be used with a Subscriber as source, and will delay incoming messages until they can be transformed to the specified TF target frames. If the filter input is not unary, only the first argument is examined, which must have an accessible ROS header as determined by the ros::message_traits
template.
|
inherited |
Grouped input types.
This type can be used to define sources with matching types.
|
inherited |
Grouped output types.
This type can be used to define sinks with matching types.
|
inlinenoexcept |
Empty constructor.
Constructs an uninitialized filter object. You need to call init() before you can use the object.
|
noexcept |
Construct and initialize the filter.
The constructor calls init() and set_target_frame() for you.
bc
a TF2 buffer instance target_frame
the TF target frame for the incoming messages queue_size
the maximum number of queued messages nh
the ROS node handle whose callback queue is used to pass transformable messages
|
noexcept |
Construct and initialize the filter.
The constructor calls init() and set_target_frame() for you.
bc
a TF2 buffer instance target_frame
the TF target frame for the incoming messages queue_size
the maximum number of queued messages cbq
the ROS callback queue that is used to pass transformable messages. If nullptr
, the send() function is called directly from the TF2 buffer callback or receive() method.
|
noexcept |
Construct and initialize the filter.
The constructor calls init() and set_target_frames() for you.
bc
a TF2 buffer instance target_frames
the TF target frames for the incoming messages. Passed message will be transformable to all these frames. queue_size
the maximum number of queued messages nh
the ROS node handle whose callback queue is used to pass transformable messages
|
noexcept |
Construct and initialize the filter.
The constructor calls init() and set_target_frames() for you.
bc
a TF2 buffer instance target_frames
the TF target frames for the incoming messages. Passed message will be transformable to all these frames. queue_size
the maximum number of queued messages cbq
the ROS callback queue that is used to pass transformable messages. If nullptr
, the send() function is called directly from the TF2 buffer callback or receive() method.
|
noexceptinherited |
Connect this source to a sink.
Can be called multiple times to connect multiple sinks; in that case, the sinks receive data in the same order as they have been connected. This function does basically the same thing as Sink::connect_to_source(), only from the opposite point of view.
dst
the sink that is to be connected
|
noexceptinherited |
Connect this sink to a source.
Can be called multiple times to connect multiple sources; in that case, the sink receives data from all connected sources. This function does basically the same thing as Source::connect_to_sink(), only from the opposite point of view.
src
the source that is to be connected
|
noexceptinherited |
Disconnect from all connected sinks.
Severs the connection to all sinks, turning the send() method into a no-op.
|
noexceptinherited |
Disconnect from all connected sources.
Severs the connection to all sources. The receive() method will not be called any more.
|
noexcept |
Initialize the filter.
This function allocates internal data structures and makes the filter operational. If the function is called on an already initialized filter, the filter is reinitialized and reset() is called implicitly.
bc
a TF2 buffer instance queue_size
the maximum number of queued messages nh
the ROS node handle whose callback queue is used to pass transformable messages
|
noexcept |
Initialize the filter.
This function allocates internal data structures and makes the filter operational. If the function is called on an already initialized filter, the filter is reinitialized and reset() is called implicitly.
bc
a TF2 buffer instance queue_size
the maximum number of queued messages cbq
the ROS callback queue that is used to pass transformable messages. If nullptr
, the send() function is called directly from the TF2 buffer callback or receive() method.
|
overrideprotectedvirtual |
Process incoming data.
Derived classes need to override this method to handle all data that is to be consumed by the sink.
Implements fkie_message_filters::Sink< Inputs >.
|
overridevirtualnoexcept |
Reset filter state.
Discards all queued messages. Existing connections to sources and sinks are unaffected.
Reimplemented from fkie_message_filters::FilterBase.
|
protectedinherited |
Pass data to all connected sinks.
out
datavoid fkie_message_filters::TfFilter< Inputs >::set_filter_failure_function | ( | FilterFailureCB | cb | ) |
Register callback for failed transforms.
Whenever a message is discarded, this callback is called with the message and the reason why the TF transform failed.
cb
callback functionstd::logic_error | if the filter is uninitialized |
void fkie_message_filters::TfFilter< Inputs >::set_target_frame | ( | const std::string & | target_frame | ) |
Choose the TF target frame.
target_frame
all passed messages will be transformable to this TF framestd::logic_error | if the filter is uninitialized |
void fkie_message_filters::TfFilter< Inputs >::set_target_frames | ( | const ros::V_string & | target_frames | ) |
Choose the TF target frames.
target_frames
all passed messages will be transformable to all these TF framesstd::logic_error | if the filter is uninitialized |