Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
tf2_ros::MessageFilter< 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.h>

Inheritance diagram for tf2_ros::MessageFilter< M >:
Inheritance graph
[legend]

List of all members.

Classes

struct  CBQueueCallback
struct  MessageInfo

Public Types

typedef boost::function< void(const
MConstPtr
&, FilterFailureReason)> 
FailureCallback
typedef
boost::signals2::signal< void(const
MConstPtr
&, FilterFailureReason)> 
FailureSignal
typedef boost::shared_ptr< M
const > 
MConstPtr
typedef ros::MessageEvent< M
const > 
MEvent

Public Member Functions

void add (const MEvent &evt)
void add (const MConstPtr &message)
 Manually add a message into this filter.
void clear ()
 Clear any messages currently in the queue.
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.
virtual uint32_t getQueueSize ()
std::string getTargetFramesString ()
 Get the target frames as a string for debugging.
 MessageFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
 Constructor.
template<class F >
 MessageFilter (F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
 Constructor.
 MessageFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
 Constructor.
template<class F >
 MessageFilter (F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
 Constructor.
message_filters::Connection registerFailureCallback (const FailureCallback &callback)
 Register a callback to be called when a message is about to be dropped.
virtual void setQueueSize (uint32_t new_queue_size)
void setTargetFrame (const std::string &target_frame)
 Set the frame you need to be able to transform to before getting a message callback.
void setTargetFrames (const V_string &target_frames)
 Set the frames you need to be able to transform to before getting a message callback.
void setTolerance (const ros::Duration &tolerance)
 Set the required tolerance for the notifier to return true.
 ~MessageFilter ()
 Destructor.

Private Types

typedef std::list< MessageInfoL_MessageInfo
typedef std::vector
< tf2::TransformableRequestHandle
V_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.
void init ()
void messageDropped (const MEvent &evt, FilterFailureReason reason)
void messageReady (const MEvent &evt)
void signalFailure (const MEvent &evt, FilterFailureReason reason)
void transformable (tf2::TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time 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.
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. Used because <container>.size() may have linear cost.
L_MessageInfo messages_
boost::shared_mutex messages_mutex_
 The mutex used for locking message list operations.
ros::WallTime next_failure_warning_
uint32_t queue_size_
 The maximum number of messages we queue up.
uint64_t successful_transform_count_
V_string target_frames_
 The frames we need to be able to transform to before a message is ready.
boost::mutex target_frames_mutex_
 A mutex to protect access to the target_frames_ list and target_frames_string.
std::string target_frames_string_
ros::Duration time_tolerance_
 Provide additional tolerance on time for messages which are stamped but can have associated duration.
uint64_t transform_message_count_
bool warned_about_empty_frame_id_

Detailed Description

template<class M>
class tf2_ros::MessageFilter< 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);
tf::MessageFilter<MessageType> tf_filter(sub, tf_listener_, "/map", 10);
tf_filter.registerCallback(&MyClass::myCallback, this);

Definition at line 104 of file message_filter.h.


Member Typedef Documentation

template<class M >
typedef boost::function<void(const MConstPtr&, FilterFailureReason)> tf2_ros::MessageFilter< M >::FailureCallback

Definition at line 109 of file message_filter.h.

template<class M >
typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> tf2_ros::MessageFilter< M >::FailureSignal

Definition at line 110 of file message_filter.h.

template<class M >
typedef std::list<MessageInfo> tf2_ros::MessageFilter< M >::L_MessageInfo [private]

Definition at line 681 of file message_filter.h.

template<class M >
typedef boost::shared_ptr<M const> tf2_ros::MessageFilter< M >::MConstPtr

Reimplemented from message_filters::SimpleFilter< M >.

Definition at line 107 of file message_filter.h.

template<class M >
typedef ros::MessageEvent<M const> tf2_ros::MessageFilter< M >::MEvent

Definition at line 108 of file message_filter.h.

template<class M >
typedef std::vector<tf2::TransformableRequestHandle> tf2_ros::MessageFilter< M >::V_TransformableRequestHandle [private]

Definition at line 670 of file message_filter.h.


Constructor & Destructor Documentation

template<class M >
tf2_ros::MessageFilter< M >::MessageFilter ( tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
const ros::NodeHandle nh 
) [inline]

Constructor.

Parameters:
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 126 of file message_filter.h.

template<class M >
template<class F >
tf2_ros::MessageFilter< M >::MessageFilter ( F &  f,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
const ros::NodeHandle nh 
) [inline]

Constructor.

Parameters:
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 146 of file message_filter.h.

template<class M >
tf2_ros::MessageFilter< M >::MessageFilter ( tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
ros::CallbackQueueInterface cbqueue 
) [inline]

Constructor.

Parameters:
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 168 of file message_filter.h.

template<class M >
template<class F >
tf2_ros::MessageFilter< M >::MessageFilter ( F &  f,
tf2::BufferCore bc,
const std::string &  target_frame,
uint32_t  queue_size,
ros::CallbackQueueInterface cbqueue 
) [inline]

Constructor.

Parameters:
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 190 of file message_filter.h.

template<class M >
tf2_ros::MessageFilter< M >::~MessageFilter ( ) [inline]

Destructor.

Definition at line 215 of file message_filter.h.


Member Function Documentation

template<class M >
void tf2_ros::MessageFilter< M >::add ( const MEvent evt) [inline]

Definition at line 293 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< 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 408 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::checkFailures ( ) [inline, private]

Definition at line 554 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::clear ( ) [inline, virtual]

Clear any messages currently in the queue.

Implements tf2_ros::MessageFilterBase.

Definition at line 278 of file message_filter.h.

template<class M >
template<class F >
void tf2_ros::MessageFilter< 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 206 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::disconnectFailure ( const message_filters::Connection c) [inline, private]

Definition at line 639 of file message_filter.h.

template<class M >
virtual uint32_t tf2_ros::MessageFilter< M >::getQueueSize ( ) [inline, virtual]

Definition at line 432 of file message_filter.h.

template<class M >
std::string tf2_ros::MessageFilter< M >::getTargetFramesString ( ) [inline]

Get the target frames as a string for debugging.

Definition at line 259 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::incomingMessage ( const ros::MessageEvent< M const > &  evt) [inline, private]

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

Definition at line 549 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::init ( ) [inline, private]

Definition at line 440 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::messageDropped ( const MEvent evt,
FilterFailureReason  reason 
) [inline, private]

Definition at line 613 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::messageReady ( const MEvent evt) [inline, private]

Definition at line 626 of file message_filter.h.

template<class M >
message_filters::Connection tf2_ros::MessageFilter< 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 421 of file message_filter.h.

template<class M >
virtual void tf2_ros::MessageFilter< M >::setQueueSize ( uint32_t  new_queue_size) [inline, virtual]

Definition at line 427 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::setTargetFrame ( const std::string &  target_frame) [inline, virtual]

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

Implements tf2_ros::MessageFilterBase.

Definition at line 231 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::setTargetFrames ( const V_string target_frames) [inline, virtual]

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

Implements tf2_ros::MessageFilterBase.

Definition at line 241 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::setTolerance ( const ros::Duration tolerance) [inline, virtual]

Set the required tolerance for the notifier to return true.

Implements tf2_ros::MessageFilterBase.

Definition at line 268 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::signalFailure ( const MEvent evt,
FilterFailureReason  reason 
) [inline, private]

Definition at line 645 of file message_filter.h.

template<class M >
static std::string tf2_ros::MessageFilter< M >::stripSlash ( const std::string &  in) [inline, static, private]

Definition at line 652 of file message_filter.h.

template<class M >
void tf2_ros::MessageFilter< M >::transformable ( tf2::TransformableRequestHandle  request_handle,
const std::string &  target_frame,
const std::string &  source_frame,
ros::Time  time,
tf2::TransformableResult  result 
) [inline, private]

Definition at line 455 of file message_filter.h.


Member Data Documentation

template<class M >
tf2::BufferCore& tf2_ros::MessageFilter< M >::bc_ [private]

The Transformer used to determine if transformation data is available.

Definition at line 663 of file message_filter.h.

Definition at line 668 of file message_filter.h.

Definition at line 707 of file message_filter.h.

template<class M >
uint64_t tf2_ros::MessageFilter< M >::dropped_message_count_ [private]

Definition at line 693 of file message_filter.h.

template<class M >
uint32_t tf2_ros::MessageFilter< M >::expected_success_count_ [private]

Definition at line 685 of file message_filter.h.

template<class M >
uint64_t tf2_ros::MessageFilter< M >::failed_out_the_back_count_ [private]

Definition at line 690 of file message_filter.h.

template<class M >
FailureSignal tf2_ros::MessageFilter< M >::failure_signal_ [private]

Definition at line 704 of file message_filter.h.

template<class M >
boost::mutex tf2_ros::MessageFilter< M >::failure_signal_mutex_ [private]

Definition at line 705 of file message_filter.h.

template<class M >
uint64_t tf2_ros::MessageFilter< M >::incoming_message_count_ [private]

Definition at line 692 of file message_filter.h.

template<class M >
std::string tf2_ros::MessageFilter< M >::last_out_the_back_frame_ [private]

Definition at line 696 of file message_filter.h.

template<class M >
ros::Time tf2_ros::MessageFilter< M >::last_out_the_back_stamp_ [private]

Definition at line 695 of file message_filter.h.

Definition at line 702 of file message_filter.h.

template<class M >
uint32_t tf2_ros::MessageFilter< M >::message_count_ [private]

The number of messages in the list. Used because <container>.size() may have linear cost.

Definition at line 683 of file message_filter.h.

template<class M >
L_MessageInfo tf2_ros::MessageFilter< M >::messages_ [private]

Definition at line 682 of file message_filter.h.

template<class M >
boost::shared_mutex tf2_ros::MessageFilter< M >::messages_mutex_ [private]

The mutex used for locking message list operations.

Definition at line 684 of file message_filter.h.

template<class M >
ros::WallTime tf2_ros::MessageFilter< M >::next_failure_warning_ [private]

Definition at line 698 of file message_filter.h.

template<class M >
uint32_t tf2_ros::MessageFilter< M >::queue_size_ [private]

The maximum number of messages we queue up.

Definition at line 667 of file message_filter.h.

template<class M >
uint64_t tf2_ros::MessageFilter< M >::successful_transform_count_ [private]

Definition at line 689 of file message_filter.h.

template<class M >
V_string tf2_ros::MessageFilter< M >::target_frames_ [private]

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

Definition at line 664 of file message_filter.h.

template<class M >
boost::mutex tf2_ros::MessageFilter< M >::target_frames_mutex_ [private]

A mutex to protect access to the target_frames_ list and target_frames_string.

Definition at line 666 of file message_filter.h.

template<class M >
std::string tf2_ros::MessageFilter< M >::target_frames_string_ [private]

Definition at line 665 of file message_filter.h.

template<class M >
ros::Duration tf2_ros::MessageFilter< M >::time_tolerance_ [private]

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

Definition at line 700 of file message_filter.h.

template<class M >
uint64_t tf2_ros::MessageFilter< M >::transform_message_count_ [private]

Definition at line 691 of file message_filter.h.

template<class M >
bool tf2_ros::MessageFilter< M >::warned_about_empty_frame_id_ [private]

Definition at line 687 of file message_filter.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 2 2017 02:24:43