tf::MessageNotifier< MessageT > Class Template Reference

Queues messages that include a Header until there is transform data available for the time the timestamp on the message. More...

#include <message_notifier.h>

Inheritance diagram for tf::MessageNotifier< MessageT >:
Inheritance graph
[legend]

List of all members.

Classes

class  MessageDeleter
 Since we allocate with our own special functions, we need to also delete using them. This provides a deletion interface for the boost::shared_ptr. More...

Public Types

typedef boost::function< void(const
MessagePtr &)> 
Callback
typedef boost::shared_ptr
< MessageT > 
MessagePtr

Public Member Functions

void clear ()
 Clear any messages currently in the queue.
void enqueueMessage (const MessagePtr &message)
std::string getTargetFramesString ()
 Get the target frames as a string for debugging.
ROSCPP_DEPRECATED MessageNotifier (Transformer &tf, Callback callback, const std::string &topic, const std::string &target_frame, uint32_t queue_size)
 Constructor.
void setTargetFrame (const std::vector< std::string > &target_frames)
 Set the frames you need to be able to transform to before getting a message callback.
void setTargetFrame (const std::string &target_frame)
 Set the frame 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.
void setTopic (const std::string &topic)
 Set the topic to listen on.
void subscribeToMessage ()
 Subscribe to the message topic.
void unsubscribeFromMessage ()
 Unsubscribe from the message topic.
 ~MessageNotifier ()
 Destructor.

Private Types

typedef std::list< MessagePtrL_Message
typedef std::vector< MessagePtrV_Message

Private Member Functions

void checkFailures ()
void gatherReadyMessages (V_Message &to_notify)
 Gather any messages ready to be transformed.
void incomingMessage (typename MessageT::ConstPtr msg)
 Callback that happens when we receive a message on the message topic.
void incomingTFMessage (const tf::tfMessage::ConstPtr msg)
 Callback that happens when we receive a message on the TF message topic.
void notify (V_Message &to_notify)
 Calls the notification callback on each message in the passed vector.
void processNewMessages (V_Message &messages)
 Adds messages into the message list, removing old messages if necessary.
void workerThread ()
 Entry point into the worker thread that does all our actual work, including calling the notification callback.

Private Attributes

Callback callback_
 The callback to call when a message is ready.
bool destructing_
 Used to notify the worker thread that it needs to shutdown.
uint64_t dropped_message_count_
uint64_t failed_out_the_back_count_
uint64_t failed_transform_count_
uint64_t incoming_message_count_
std::string last_out_the_back_frame_
ros::Time last_out_the_back_stamp_
boost::mutex list_mutex_
 The mutex used for locking message list operations.
uint32_t message_count_
 The number of messages in the list. Used because messages_.size() has linear cost.
L_Message messages_
 The message list.
boost::condition_variable new_data_
 Condition variable used for waking the worker thread.
V_Message new_message_queue_
 Queues messages to later be processed by the worker thread.
bool new_messages_
 Used to skip waiting on new_data_ if new messages have come in while calling back.
volatile bool new_transforms_
 Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming data.
ros::Time next_failure_warning_
ros::NodeHandle node_
 The node used to subscribe to the topic.
boost::mutex queue_mutex_
 The mutex used for locking message queue operations.
uint32_t queue_size_
 The maximum number of messages we queue up.
ros::Subscriber subscriber_
uint64_t successful_transform_count_
std::vector< std::string > target_frames_
 The frames we need to be able to transform to before a message is ready.
std::string target_frames_string_
boost::mutex target_frames_string_mutex_
Transformer & tf_
 The Transformer used to determine if transformation data is available.
ros::Subscriber tf_subscriber_1_
ros::Subscriber tf_subscriber_2_
boost::thread thread_handle_
 Thread handle for the worker thread.
ros::Duration time_tolerance_
 Provide additional tolerance on time for messages which are stamped but can have associated duration.
std::string topic_
 The topic to listen on.
uint64_t transform_message_count_

Detailed Description

template<class MessageT>
class tf::MessageNotifier< MessageT >

Queues messages that include a Header until there is transform data available for the time the timestamp on the message.

Deprecated:
Deprecated in favor of tf::MessageFilter For use instead of extrapolation, MessageNotifier provides a way of waiting until it is possible to transform a message before getting a callback notifying that the message is available.

THE CALLBACK

The callback takes one argument, which is a boost shared_ptr to a message. MessageNotifier provides a MessagePtr typedef, so the signature of the callback is:

 void funcName(const MessageNotifier<MessageT>::MessagePtr& message);
 

A bare function can be passed directly as the callback. Methods must be passed using boost::bind. For example

 boost::bind(&MyObject::funcName, this, _1);
 

The message is not locked when your callback is invoked.

THREADING

MessageNotifier spins up a single thread to call your callback from, so that it's possible to do a lot of work in your callback without blocking the rest of the application.

Definition at line 110 of file message_notifier.h.


Member Typedef Documentation

template<class MessageT >
typedef boost::function<void(const MessagePtr&)> tf::MessageNotifier< MessageT >::Callback

Definition at line 114 of file message_notifier.h.

template<class MessageT >
typedef std::list<MessagePtr> tf::MessageNotifier< MessageT >::L_Message [private]

Definition at line 295 of file message_notifier.h.

template<class MessageT >
typedef boost::shared_ptr<MessageT> tf::MessageNotifier< MessageT >::MessagePtr

Definition at line 113 of file message_notifier.h.

template<class MessageT >
typedef std::vector<MessagePtr> tf::MessageNotifier< MessageT >::V_Message [private]

Definition at line 294 of file message_notifier.h.


Constructor & Destructor Documentation

template<class MessageT >
ROSCPP_DEPRECATED tf::MessageNotifier< MessageT >::MessageNotifier ( Transformer &  tf,
Callback  callback,
const std::string &  topic,
const std::string &  target_frame,
uint32_t  queue_size 
) [inline]

Constructor.

Parameters:
tf The Transformer to use for checking if the transform data is available
callback The function to call when a message is ready to be transformed
topic The topic to listen on
target_frame The frame we need to be able to transform to before a message is ready
queue_size The number of messages to keep around waiting for transform data.
Note:
A queue size of 0 means infinite, which can be dangerous

Definition at line 125 of file message_notifier.h.

template<class MessageT >
tf::MessageNotifier< MessageT >::~MessageNotifier (  )  [inline]

Destructor.

Definition at line 161 of file message_notifier.h.


Member Function Documentation

template<class MessageT >
void tf::MessageNotifier< MessageT >::checkFailures (  )  [inline, private]

Definition at line 526 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::clear (  )  [inline, virtual]

Clear any messages currently in the queue.

Implements tf::MessageNotifierBase.

Definition at line 241 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::enqueueMessage ( const MessagePtr message  )  [inline]

Definition at line 251 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::gatherReadyMessages ( V_Message to_notify  )  [inline, private]

Gather any messages ready to be transformed.

Parameters:
to_notify Filled with the messages ready to be transformed, in the order they were received
Note:
Assumes the message list is already locked

Todo:
combine getLatestCommonTime call with the canTransform call

Definition at line 302 of file message_notifier.h.

template<class MessageT >
std::string tf::MessageNotifier< MessageT >::getTargetFramesString (  )  [inline]

Get the target frames as a string for debugging.

Definition at line 212 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::incomingMessage ( typename MessageT::ConstPtr  msg  )  [inline, private]

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

Definition at line 501 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::incomingTFMessage ( const tf::tfMessage::ConstPtr  msg  )  [inline, private]

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

Definition at line 518 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::notify ( V_Message to_notify  )  [inline, private]

Calls the notification callback on each message in the passed vector.

Parameters:
to_notify The list of messages to call the callback on

Definition at line 393 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::processNewMessages ( V_Message messages  )  [inline, private]

Adds messages into the message list, removing old messages if necessary.

Definition at line 406 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::setTargetFrame ( const std::vector< std::string > &  target_frames  )  [inline, virtual]

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

Implements tf::MessageNotifierBase.

Definition at line 194 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::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 tf::MessageNotifierBase.

Definition at line 184 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::setTolerance ( const ros::Duration &  tolerance  )  [inline, virtual]

Set the required tolerance for the notifier to return true.

Implements tf::MessageNotifierBase.

Definition at line 233 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::setTopic ( const std::string &  topic  )  [inline, virtual]

Set the topic to listen on.

Implements tf::MessageNotifierBase.

Definition at line 221 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::subscribeToMessage (  )  [inline, virtual]

Subscribe to the message topic.

Implements tf::MessageNotifierBase.

Definition at line 272 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::unsubscribeFromMessage (  )  [inline, virtual]

Unsubscribe from the message topic.

Implements tf::MessageNotifierBase.

Definition at line 284 of file message_notifier.h.

template<class MessageT >
void tf::MessageNotifier< MessageT >::workerThread (  )  [inline, private]

Entry point into the worker thread that does all our actual work, including calling the notification callback.

Definition at line 436 of file message_notifier.h.


Member Data Documentation

template<class MessageT >
Callback tf::MessageNotifier< MessageT >::callback_ [private]

The callback to call when a message is ready.

Definition at line 558 of file message_notifier.h.

template<class MessageT >
bool tf::MessageNotifier< MessageT >::destructing_ [private]

Used to notify the worker thread that it needs to shutdown.

Definition at line 569 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::dropped_message_count_ [private]

Definition at line 582 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::failed_out_the_back_count_ [private]

Definition at line 579 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::failed_transform_count_ [private]

Definition at line 578 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::incoming_message_count_ [private]

Definition at line 581 of file message_notifier.h.

template<class MessageT >
std::string tf::MessageNotifier< MessageT >::last_out_the_back_frame_ [private]

Definition at line 585 of file message_notifier.h.

template<class MessageT >
ros::Time tf::MessageNotifier< MessageT >::last_out_the_back_stamp_ [private]

Definition at line 584 of file message_notifier.h.

template<class MessageT >
boost::mutex tf::MessageNotifier< MessageT >::list_mutex_ [private]

The mutex used for locking message list operations.

Definition at line 567 of file message_notifier.h.

template<class MessageT >
uint32_t tf::MessageNotifier< MessageT >::message_count_ [private]

The number of messages in the list. Used because messages_.size() has linear cost.

Definition at line 566 of file message_notifier.h.

template<class MessageT >
L_Message tf::MessageNotifier< MessageT >::messages_ [private]

The message list.

Definition at line 565 of file message_notifier.h.

template<class MessageT >
boost::condition_variable tf::MessageNotifier< MessageT >::new_data_ [private]

Condition variable used for waking the worker thread.

Definition at line 571 of file message_notifier.h.

template<class MessageT >
V_Message tf::MessageNotifier< MessageT >::new_message_queue_ [private]

Queues messages to later be processed by the worker thread.

Definition at line 574 of file message_notifier.h.

template<class MessageT >
bool tf::MessageNotifier< MessageT >::new_messages_ [private]

Used to skip waiting on new_data_ if new messages have come in while calling back.

Definition at line 572 of file message_notifier.h.

template<class MessageT >
volatile bool tf::MessageNotifier< MessageT >::new_transforms_ [private]

Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming data.

Definition at line 573 of file message_notifier.h.

template<class MessageT >
ros::Time tf::MessageNotifier< MessageT >::next_failure_warning_ [private]

Definition at line 587 of file message_notifier.h.

template<class MessageT >
ros::NodeHandle tf::MessageNotifier< MessageT >::node_ [private]

The node used to subscribe to the topic.

Definition at line 555 of file message_notifier.h.

template<class MessageT >
boost::mutex tf::MessageNotifier< MessageT >::queue_mutex_ [private]

The mutex used for locking message queue operations.

Definition at line 575 of file message_notifier.h.

template<class MessageT >
uint32_t tf::MessageNotifier< MessageT >::queue_size_ [private]

The maximum number of messages we queue up.

Definition at line 563 of file message_notifier.h.

template<class MessageT >
ros::Subscriber tf::MessageNotifier< MessageT >::subscriber_ [private]

Definition at line 556 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::successful_transform_count_ [private]

Definition at line 577 of file message_notifier.h.

template<class MessageT >
std::vector<std::string> tf::MessageNotifier< MessageT >::target_frames_ [private]

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

Definition at line 559 of file message_notifier.h.

template<class MessageT >
std::string tf::MessageNotifier< MessageT >::target_frames_string_ [private]

Definition at line 560 of file message_notifier.h.

template<class MessageT >
boost::mutex tf::MessageNotifier< MessageT >::target_frames_string_mutex_ [private]

Definition at line 561 of file message_notifier.h.

template<class MessageT >
Transformer& tf::MessageNotifier< MessageT >::tf_ [private]

The Transformer used to determine if transformation data is available.

Definition at line 554 of file message_notifier.h.

template<class MessageT >
ros::Subscriber tf::MessageNotifier< MessageT >::tf_subscriber_1_ [private]

Definition at line 557 of file message_notifier.h.

template<class MessageT >
ros::Subscriber tf::MessageNotifier< MessageT >::tf_subscriber_2_ [private]

Definition at line 557 of file message_notifier.h.

template<class MessageT >
boost::thread tf::MessageNotifier< MessageT >::thread_handle_ [private]

Thread handle for the worker thread.

Definition at line 570 of file message_notifier.h.

template<class MessageT >
ros::Duration tf::MessageNotifier< MessageT >::time_tolerance_ [private]

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

Definition at line 589 of file message_notifier.h.

template<class MessageT >
std::string tf::MessageNotifier< MessageT >::topic_ [private]

The topic to listen on.

Definition at line 562 of file message_notifier.h.

template<class MessageT >
uint64_t tf::MessageNotifier< MessageT >::transform_message_count_ [private]

Definition at line 580 of file message_notifier.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


door_handle_detector
Author(s): Radu Bogdan Rusu, Marius
autogenerated on Fri Jan 11 09:42:08 2013