Classes | Public Types | Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
fkie_message_filters::TfFilter< Inputs > Class Template Reference

Wait for TF transformations for incoming messages. More...

#include <tf_filter.h>

Inheritance diagram for fkie_message_filters::TfFilter< Inputs >:
Inheritance graph
[legend]

Classes

struct  Impl
 
class  RosCB
 

Public Types

using FilterFailureCB = std::function< void(const Inputs &..., TfFilterResult)>
 Callback for failed transform queries. More...
 
- Public Types inherited from fkie_message_filters::Sink< Inputs... >
using Input = IO< Inputs... >
 Grouped input types. More...
 
- Public Types inherited from fkie_message_filters::Source< IO< Inputs... > >
using Output = IO< Outputs... >
 Grouped output types. More...
 

Public Member Functions

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...
 
 TfFilter () noexcept
 Empty constructor. 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...
 
 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...
 
- Public Member Functions inherited from fkie_message_filters::Sink< Inputs... >
Connection connect_to_source (Source< Inputs... > &src) noexcept
 Connect this sink to a source. More...
 
void disconnect_from_all_sources () noexcept
 Disconnect from all connected sources. More...
 
virtual ~Sink ()
 
- Public Member Functions inherited from fkie_message_filters::FilterBase
virtual ~FilterBase ()
 
- Public Member Functions inherited from fkie_message_filters::Source< IO< Inputs... > >
Connection connect_to_sink (Sink< Outputs... > &dst) noexcept
 Connect this source to a sink. More...
 
void disconnect_from_all_sinks () noexcept
 Disconnect from all connected sinks. More...
 
virtual ~Source ()
 

Protected Member Functions

void receive (const Inputs &... in) override
 Process incoming data. More...
 
- Protected Member Functions inherited from fkie_message_filters::Source< IO< Inputs... > >
void send (const Outputs &... out)
 Pass data to all connected sinks. More...
 

Private Types

using MessageTuple = std::tuple< Inputs... >
 

Private Member Functions

void report_failure (std::unique_lock< std::mutex > &, const MessageTuple &, TfFilterResult)
 
void send_message (std::unique_lock< std::mutex > &, const MessageTuple &m)
 
void transformable (tf2::TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, tf2::TransformableResult result)
 

Private Attributes

std::shared_ptr< Implimpl_
 

Additional Inherited Members

- Static Public Attributes inherited from fkie_message_filters::Sink< Inputs... >
static constexpr std::size_t NUM_INPUTS
 Number of input arguments. More...
 
- Static Public Attributes inherited from fkie_message_filters::Source< IO< Inputs... > >
static constexpr std::size_t NUM_OUTPUTS
 Number of output arguments. More...
 

Detailed Description

template<class... Inputs>
class fkie_message_filters::TfFilter< Inputs >

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.

sub.subscribe(nh, "topic", 10);
flt.init(tf2_buffer, "target_frame", 10, nh);
mf::chain(sub, flt);

Definition at line 90 of file tf_filter.h.

Member Typedef Documentation

◆ FilterFailureCB

template<class... Inputs>
using fkie_message_filters::TfFilter< Inputs >::FilterFailureCB = std::function<void(const Inputs&..., TfFilterResult)>

Callback for failed transform queries.

Definition at line 94 of file tf_filter.h.

◆ MessageTuple

template<class... Inputs>
using fkie_message_filters::TfFilter< Inputs >::MessageTuple = std::tuple<Inputs...>
private

Definition at line 210 of file tf_filter.h.

Constructor & Destructor Documentation

◆ TfFilter() [1/5]

template<class... Inputs>
fkie_message_filters::TfFilter< Inputs >::TfFilter ( )
inlinenoexcept

Empty constructor.

Constructs an uninitialized filter object. You need to call init() before you can use the object.

Definition at line 100 of file tf_filter.h.

◆ TfFilter() [2/5]

template<class... Inputs>
fkie_message_filters::TfFilter< Inputs >::TfFilter ( tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
const ros::NodeHandle nh 
)
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

\nothrow

Definition at line 165 of file tf_filter_impl.h.

◆ TfFilter() [3/5]

template<class... Inputs>
fkie_message_filters::TfFilter< Inputs >::TfFilter ( tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
ros::CallbackQueueInterface cbq 
)
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.

\nothrow

Definition at line 172 of file tf_filter_impl.h.

◆ TfFilter() [4/5]

template<class... Inputs>
fkie_message_filters::TfFilter< Inputs >::TfFilter ( tf2::BufferCore bc,
const ros::V_string target_frames,
uint32_t  queue_size,
const ros::NodeHandle nh 
)
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

\nothrow

Definition at line 179 of file tf_filter_impl.h.

◆ TfFilter() [5/5]

template<class... Inputs>
fkie_message_filters::TfFilter< Inputs >::TfFilter ( tf2::BufferCore bc,
const ros::V_string target_frames,
uint32_t  queue_size,
ros::CallbackQueueInterface cbq 
)
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.

\nothrow

Definition at line 186 of file tf_filter_impl.h.

Member Function Documentation

◆ init() [1/2]

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::init ( tf2::BufferCore bc,
uint32_t  queue_size,
const ros::NodeHandle nh 
)
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

\nothrow

Definition at line 207 of file tf_filter_impl.h.

◆ init() [2/2]

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::init ( tf2::BufferCore bc,
uint32_t  queue_size,
ros::CallbackQueueInterface cbq 
)
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.

\nothrow

Definition at line 193 of file tf_filter_impl.h.

◆ receive()

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::receive ( const Inputs &...  in)
overrideprotectedvirtual

Process incoming data.

Derived classes need to override this method to handle all data that is to be consumed by the sink.

\abstractthrow

Implements fkie_message_filters::Sink< Inputs... >.

Definition at line 254 of file tf_filter_impl.h.

◆ report_failure()

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::report_failure ( std::unique_lock< std::mutex > &  lock,
const MessageTuple msg,
TfFilterResult  reason 
)
private

Definition at line 339 of file tf_filter_impl.h.

◆ reset()

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::reset
overridevirtualnoexcept

Reset filter state.

Discards all queued messages. Existing connections to sources and sinks are unaffected.

\nothrow

Reimplemented from fkie_message_filters::FilterBase.

Definition at line 232 of file tf_filter_impl.h.

◆ send_message()

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::send_message ( std::unique_lock< std::mutex > &  lock,
const MessageTuple m 
)
private

Definition at line 364 of file tf_filter_impl.h.

◆ set_filter_failure_function()

template<class... Inputs>
void 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 function
Exceptions
std::logic_errorif the filter is uninitialized

Definition at line 246 of file tf_filter_impl.h.

◆ set_target_frame()

template<class... Inputs>
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 frame
Exceptions
std::logic_errorif the filter is uninitialized

Definition at line 226 of file tf_filter_impl.h.

◆ set_target_frames()

template<class... Inputs>
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 frames
Exceptions
std::logic_errorif the filter is uninitialized

Definition at line 213 of file tf_filter_impl.h.

◆ transformable()

template<class... Inputs>
void fkie_message_filters::TfFilter< Inputs >::transformable ( tf2::TransformableRequestHandle  request_handle,
const std::string &  target_frame,
const std::string &  source_frame,
ros::Time  time,
tf2::TransformableResult  result 
)
private

Definition at line 299 of file tf_filter_impl.h.

Member Data Documentation

◆ impl_

template<class... Inputs>
std::shared_ptr<Impl> fkie_message_filters::TfFilter< Inputs >::impl_
private

Definition at line 212 of file tf_filter.h.


The documentation for this class was generated from the following files:
fkie_message_filters::Subscriber::subscribe
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
Convenience function to subscribe to a ROS topic.
Definition: subscriber_impl.h:77
fkie_message_filters
Definition: buffer.h:33
fkie_message_filters::chain
void chain(Filter1 &flt1, Filter2 &flt2, MoreFilters &... filters) noexcept
Convenience function to chain multiple filters.
Definition: filter_impl.h:71
fkie_message_filters::Subscriber
Subscribe to a ROS topic as data provider.
Definition: subscriber.h:72
fkie_message_filters::TfFilter
Wait for TF transformations for incoming messages.
Definition: tf_filter.h:90
fkie_message_filters::TfFilter::init
void init(tf2::BufferCore &bc, uint32_t queue_size, const ros::NodeHandle &nh) noexcept
Initialize the filter.
Definition: tf_filter_impl.h:207
ros::NodeHandle


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Wed Mar 2 2022 00:18:57