List of all members
fkie_message_filters::TfFilter< IO< Inputs... > > Class Template Reference

#include <tf_filter.h>

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

Additional Inherited Members

- Public Types inherited from fkie_message_filters::TfFilter< Inputs... >
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 inherited from fkie_message_filters::TfFilter< Inputs... >
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 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...
 
- 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 ()
 
- 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...
 
- Protected Member Functions inherited from fkie_message_filters::TfFilter< Inputs... >
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...
 

Detailed Description

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

Definition at line 202 of file tf_filter.h.


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


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:44