Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
cras::TfMessageFilter< M, > 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.hpp>

Inheritance diagram for cras::TfMessageFilter< M, >:
Inheritance graph
[legend]

Classes

struct  CBQueueCallback
 
struct  MessageInfo
 

Public Types

typedef boost::function< void(const MConstPtr &, tf2_ros::FilterFailureReason)> FailureCallback
 
typedef boost::signals2::signal< void(const MConstPtr &, tf2_ros::FilterFailureReason)> FailureSignal
 
typedef boost::shared_ptr< M const > MConstPtr
 
typedef ros::MessageEvent< M const > MEvent
 
- Public Types inherited from tf2_ros::MessageFilterBase
typedef std::vector< std::string > V_string
 
- Public Types inherited from message_filters::SimpleFilter< M >
typedef boost::function< void(const MConstPtr &)> Callback
 
typedef boost::function< void(const EventType &)> EventCallback
 
typedef ros::MessageEvent< M const > EventType
 
typedef boost::shared_ptr< M const > MConstPtr
 

Public Member Functions

void add (const MConstPtr &message)
 Manually add a message into this filter. More...
 
void add (const MEvent &evt)
 
void clear () override
 Clear any messages currently in the queue. More...
 
template<class F >
void connectInput (F &f)
 Connect this filter's input to another filter's output. More...
 
virtual uint32_t getQueueSize ()
 
std::string getTargetFramesString ()
 Get the target frames as a string for debugging. More...
 
message_filters::Connection registerFailureCallback (const FailureCallback &callback)
 Register a callback to be called when a message is about to be dropped. More...
 
virtual void setQueueSize (uint32_t new_queue_size)
 
void setTargetFrame (const std::string &target_frame) override
 Set the frame you need to be able to transform to before getting a message callback. More...
 
void setTargetFrames (const V_string &target_frames) override
 Set the frames you need to be able to transform to before getting a message callback. More...
 
void setTolerance (const ros::Duration &tolerance) override
 Set the required tolerance for the notifier to return true. More...
 
template<class F >
 TfMessageFilter (const cras::LogHelperPtr &log, F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
 Constructor. More...
 
template<class F >
 TfMessageFilter (const cras::LogHelperPtr &log, F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
 Constructor. More...
 
 TfMessageFilter (const cras::LogHelperPtr &log, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
 Constructor. More...
 
 TfMessageFilter (const cras::LogHelperPtr &log, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
 Constructor. More...
 
 ~TfMessageFilter () override
 Destructor. More...
 
- Public Member Functions inherited from tf2_ros::MessageFilterBase
virtual ~MessageFilterBase ()
 
- Public Member Functions inherited from message_filters::SimpleFilter< M >
const std::string & getName ()
 
Connection registerCallback (const boost::function< void(P)> &callback)
 
Connection registerCallback (const C &callback)
 
Connection registerCallback (void(*callback)(P))
 
Connection registerCallback (void(T::*callback)(P), T *t)
 
void setName (const std::string &name)
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 This is the function picked up by CRAS_* logging macros. More...
 
 HasLogger (const ::cras::LogHelperPtr &log)
 Associate the logger with this interface. More...
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 Set the logger to be used for logging. More...
 

Private Types

typedef std::list< MessageInfoL_MessageInfo
 
typedef std::vector< tf2::TransformableRequestHandleV_TransformableRequestHandle
 

Private Member Functions

void checkFailures ()
 
void disconnectFailure (const message_filters::Connection &c)
 
void incomingMessage (const ros::MessageEvent< M const > &evt)
 Callback that happens when we receive a message on the message topic. More...
 
void init ()
 
void messageDropped (const MEvent &evt, tf2_ros::FilterFailureReason reason)
 
void messageReady (const MEvent &evt)
 
void signalFailure (const MEvent &evt, tf2_ros::FilterFailureReason reason)
 
void transformable (tf2::TransformableRequestHandle request_handle, const std::string &, const std::string &, ros::Time, tf2::TransformableResult result)
 

Static Private Member Functions

static std::string stripSlash (const std::string &in)
 

Private Attributes

tf2::BufferCorebc_
 The Transformer used to determine if transformation data is available. More...
 
tf2::TransformableCallbackHandle callback_handle_
 
ros::CallbackQueueInterfacecallback_queue_
 
uint64_t dropped_message_count_
 
uint32_t expected_success_count_
 
uint64_t failed_out_the_back_count_
 
FailureSignal failure_signal_
 
boost::mutex failure_signal_mutex_
 
uint64_t incoming_message_count_
 
std::string last_out_the_back_frame_
 
ros::Time last_out_the_back_stamp_
 
message_filters::Connection message_connection_
 
uint32_t message_count_
 The number of messages in the list. More...
 
L_MessageInfo messages_
 
boost::shared_mutex messages_mutex_
 The mutex used for locking message list operations. More...
 
ros::WallTime next_failure_warning_
 
uint32_t queue_size_
 The maximum number of messages we queue up. More...
 
uint64_t successful_transform_count_
 
V_string target_frames_
 The frames we need to be able to transform to before a message is ready. More...
 
boost::mutex target_frames_mutex_
 A mutex to protect access to target_frames_ and target_frames_string_. More...
 
std::string target_frames_string_
 
ros::Duration time_tolerance_
 Provide additional tolerance on time for messages which are stamped but can have associated duration. More...
 
uint64_t transform_message_count_
 
bool warned_about_empty_frame_id_
 

Additional Inherited Members

- Protected Member Functions inherited from message_filters::SimpleFilter< M >
void signalMessage (const MConstPtr &msg)
 
void signalMessage (const ros::MessageEvent< M const > &event)
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 Log helper. More...
 

Detailed Description

template<class M, typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
class cras::TfMessageFilter< M, >

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 roscpp'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_handle_, "topic", 10);
cras::TFMessageFilter<MessageType> tf_filter(log, sub, tf_buffer_, "/map", 10, 0);
tf_filter.registerCallback(&MyClass::myCallback, this);

Definition at line 95 of file message_filter.hpp.

Member Typedef Documentation

◆ FailureCallback

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef boost::function<void(const MConstPtr&, tf2_ros::FilterFailureReason)> cras::TfMessageFilter< M, >::FailureCallback

Definition at line 101 of file message_filter.hpp.

◆ FailureSignal

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef boost::signals2::signal<void(const MConstPtr&, tf2_ros::FilterFailureReason)> cras::TfMessageFilter< M, >::FailureSignal

Definition at line 102 of file message_filter.hpp.

◆ L_MessageInfo

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef std::list<MessageInfo> cras::TfMessageFilter< M, >::L_MessageInfo
private

Definition at line 694 of file message_filter.hpp.

◆ MConstPtr

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef boost::shared_ptr<M const> cras::TfMessageFilter< M, >::MConstPtr

Definition at line 99 of file message_filter.hpp.

◆ MEvent

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef ros::MessageEvent<M const> cras::TfMessageFilter< M, >::MEvent

Definition at line 100 of file message_filter.hpp.

◆ V_TransformableRequestHandle

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
typedef std::vector<tf2::TransformableRequestHandle> cras::TfMessageFilter< M, >::V_TransformableRequestHandle
private

Definition at line 683 of file message_filter.hpp.

Constructor & Destructor Documentation

◆ TfMessageFilter() [1/4]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
cras::TfMessageFilter< M, >::TfMessageFilter ( const cras::LogHelperPtr log,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
const ros::NodeHandle nh 
)
inline

Constructor.

Parameters
logThe logger.
bcThe tf2::BufferCore 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).
nhThe NodeHandle whose callback queue we should add callbacks to

Definition at line 114 of file message_filter.hpp.

◆ TfMessageFilter() [2/4]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
template<class F >
cras::TfMessageFilter< M, >::TfMessageFilter ( const cras::LogHelperPtr log,
F &  f,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
const ros::NodeHandle nh 
)
inline

Constructor.

Parameters
logThe logger.
fThe filter to connect this filter's input to. Often will be a message_filters::Subscriber.
bcThe tf2::BufferCore 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).
nhThe NodeHandle whose callback queue we should add callbacks to

Definition at line 135 of file message_filter.hpp.

◆ TfMessageFilter() [3/4]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
cras::TfMessageFilter< M, >::TfMessageFilter ( const cras::LogHelperPtr log,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
ros::CallbackQueueInterface cbqueue 
)
inline

Constructor.

Parameters
logThe logger.
bcThe tf2::BufferCore 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).
cbqueueThe callback queue to add callbacks to. If NULL, callbacks will happen from whatever thread either a) add() is called, which will generally be when the previous filter in the chain outputs a message, or b) tf2::BufferCore::setTransform() is called

Definition at line 158 of file message_filter.hpp.

◆ TfMessageFilter() [4/4]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
template<class F >
cras::TfMessageFilter< M, >::TfMessageFilter ( const cras::LogHelperPtr log,
F &  f,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
ros::CallbackQueueInterface cbqueue 
)
inline

Constructor.

Parameters
logThe logger.
fThe filter to connect this filter's input to. Often will be a message_filters::Subscriber.
bcThe tf2::BufferCore 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).
cbqueueThe callback queue to add callbacks to. If NULL, callbacks will happen from whatever thread either a) add() is called, which will generally be when the previous filter in the chain outputs a message, or b) tf2::BufferCore::setTransform() is called

Definition at line 181 of file message_filter.hpp.

◆ ~TfMessageFilter()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
cras::TfMessageFilter< M, >::~TfMessageFilter ( )
inlineoverride

Destructor.

Definition at line 207 of file message_filter.hpp.

Member Function Documentation

◆ add() [1/2]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::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

Definition at line 412 of file message_filter.hpp.

◆ add() [2/2]

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::add ( const MEvent evt)
inline

Definition at line 292 of file message_filter.hpp.

◆ checkFailures()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::checkFailures ( )
inlineprivate

Definition at line 562 of file message_filter.hpp.

◆ clear()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::clear ( )
inlineoverridevirtual

Clear any messages currently in the queue.

Implements tf2_ros::MessageFilterBase.

Definition at line 271 of file message_filter.hpp.

◆ connectInput()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
template<class F >
void cras::TfMessageFilter< M, >::connectInput ( F &  f)
inline

Connect this filter's input to another filter's output.

If this filter is already connected, disconnects first.

Definition at line 198 of file message_filter.hpp.

◆ disconnectFailure()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::disconnectFailure ( const message_filters::Connection c)
inlineprivate

Definition at line 652 of file message_filter.hpp.

◆ getQueueSize()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
virtual uint32_t cras::TfMessageFilter< M, >::getQueueSize ( )
inlinevirtual

Definition at line 437 of file message_filter.hpp.

◆ getTargetFramesString()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
std::string cras::TfMessageFilter< M, >::getTargetFramesString ( )
inline

Get the target frames as a string for debugging.

Definition at line 252 of file message_filter.hpp.

◆ incomingMessage()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::incomingMessage ( const ros::MessageEvent< M const > &  evt)
inlineprivate

Callback that happens when we receive a message on the message topic.

Definition at line 557 of file message_filter.hpp.

◆ init()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::init ( )
inlineprivate

Definition at line 443 of file message_filter.hpp.

◆ messageDropped()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::messageDropped ( const MEvent evt,
tf2_ros::FilterFailureReason  reason 
)
inlineprivate

Definition at line 626 of file message_filter.hpp.

◆ messageReady()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::messageReady ( const MEvent evt)
inlineprivate

Definition at line 639 of file message_filter.hpp.

◆ registerFailureCallback()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
message_filters::Connection cras::TfMessageFilter< M, >::registerFailureCallback ( const FailureCallback callback)
inline

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

Parameters
callbackThe callback to call

Definition at line 425 of file message_filter.hpp.

◆ setQueueSize()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
virtual void cras::TfMessageFilter< M, >::setQueueSize ( uint32_t  new_queue_size)
inlinevirtual

Definition at line 432 of file message_filter.hpp.

◆ setTargetFrame()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::setTargetFrame ( const std::string &  target_frame)
inlineoverridevirtual

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

Implements tf2_ros::MessageFilterBase.

Definition at line 223 of file message_filter.hpp.

◆ setTargetFrames()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::setTargetFrames ( const V_string target_frames)
inlineoverridevirtual

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

Implements tf2_ros::MessageFilterBase.

Definition at line 233 of file message_filter.hpp.

◆ setTolerance()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::setTolerance ( const ros::Duration tolerance)
inlineoverridevirtual

Set the required tolerance for the notifier to return true.

Implements tf2_ros::MessageFilterBase.

Definition at line 261 of file message_filter.hpp.

◆ signalFailure()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::signalFailure ( const MEvent evt,
tf2_ros::FilterFailureReason  reason 
)
inlineprivate

Definition at line 658 of file message_filter.hpp.

◆ stripSlash()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
static std::string cras::TfMessageFilter< M, >::stripSlash ( const std::string &  in)
inlinestaticprivate

Definition at line 665 of file message_filter.hpp.

◆ transformable()

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
void cras::TfMessageFilter< M, >::transformable ( tf2::TransformableRequestHandle  request_handle,
const std::string &  ,
const std::string &  ,
ros::Time  ,
tf2::TransformableResult  result 
)
inlineprivate

Definition at line 460 of file message_filter.hpp.

Member Data Documentation

◆ bc_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
tf2::BufferCore& cras::TfMessageFilter< M, >::bc_
private

The Transformer used to determine if transformation data is available.

Definition at line 676 of file message_filter.hpp.

◆ callback_handle_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
tf2::TransformableCallbackHandle cras::TfMessageFilter< M, >::callback_handle_
private

Definition at line 681 of file message_filter.hpp.

◆ callback_queue_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
ros::CallbackQueueInterface* cras::TfMessageFilter< M, >::callback_queue_
private

Definition at line 721 of file message_filter.hpp.

◆ dropped_message_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint64_t cras::TfMessageFilter< M, >::dropped_message_count_
private

Definition at line 706 of file message_filter.hpp.

◆ expected_success_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint32_t cras::TfMessageFilter< M, >::expected_success_count_
private

Definition at line 698 of file message_filter.hpp.

◆ failed_out_the_back_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint64_t cras::TfMessageFilter< M, >::failed_out_the_back_count_
private

Definition at line 703 of file message_filter.hpp.

◆ failure_signal_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
FailureSignal cras::TfMessageFilter< M, >::failure_signal_
private

Definition at line 718 of file message_filter.hpp.

◆ failure_signal_mutex_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
boost::mutex cras::TfMessageFilter< M, >::failure_signal_mutex_
private

Definition at line 719 of file message_filter.hpp.

◆ incoming_message_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint64_t cras::TfMessageFilter< M, >::incoming_message_count_
private

Definition at line 705 of file message_filter.hpp.

◆ last_out_the_back_frame_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
std::string cras::TfMessageFilter< M, >::last_out_the_back_frame_
private

Definition at line 709 of file message_filter.hpp.

◆ last_out_the_back_stamp_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
ros::Time cras::TfMessageFilter< M, >::last_out_the_back_stamp_
private

Definition at line 708 of file message_filter.hpp.

◆ message_connection_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
message_filters::Connection cras::TfMessageFilter< M, >::message_connection_
private

Definition at line 716 of file message_filter.hpp.

◆ message_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint32_t cras::TfMessageFilter< M, >::message_count_
private

The number of messages in the list.

Definition at line 696 of file message_filter.hpp.

◆ messages_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
L_MessageInfo cras::TfMessageFilter< M, >::messages_
private

Definition at line 695 of file message_filter.hpp.

◆ messages_mutex_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
boost::shared_mutex cras::TfMessageFilter< M, >::messages_mutex_
private

The mutex used for locking message list operations.

Definition at line 697 of file message_filter.hpp.

◆ next_failure_warning_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
ros::WallTime cras::TfMessageFilter< M, >::next_failure_warning_
private

Definition at line 711 of file message_filter.hpp.

◆ queue_size_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint32_t cras::TfMessageFilter< M, >::queue_size_
private

The maximum number of messages we queue up.

Definition at line 680 of file message_filter.hpp.

◆ successful_transform_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint64_t cras::TfMessageFilter< M, >::successful_transform_count_
private

Definition at line 702 of file message_filter.hpp.

◆ target_frames_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
V_string cras::TfMessageFilter< M, >::target_frames_
private

The frames we need to be able to transform to before a message is ready.

Definition at line 677 of file message_filter.hpp.

◆ target_frames_mutex_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
boost::mutex cras::TfMessageFilter< M, >::target_frames_mutex_
private

A mutex to protect access to target_frames_ and target_frames_string_.

Definition at line 679 of file message_filter.hpp.

◆ target_frames_string_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
std::string cras::TfMessageFilter< M, >::target_frames_string_
private

Definition at line 678 of file message_filter.hpp.

◆ time_tolerance_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
ros::Duration cras::TfMessageFilter< M, >::time_tolerance_
private

Provide additional tolerance on time for messages which are stamped but can have associated duration.

Definition at line 714 of file message_filter.hpp.

◆ transform_message_count_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
uint64_t cras::TfMessageFilter< M, >::transform_message_count_
private

Definition at line 704 of file message_filter.hpp.

◆ warned_about_empty_frame_id_

template<class M , typename ::std::enable_if_t< ros::message_traits::HasHeader< M >::value > * = nullptr>
bool cras::TfMessageFilter< M, >::warned_about_empty_frame_id_
private

Definition at line 700 of file message_filter.hpp.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Wed Apr 23 2025 02:48:43