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>
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 (Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01)) | |
Constructor. | |
template<class F > | |
MessageFilter (F &f, Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01)) | |
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 std::vector< std::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< MEvent > | L_Event |
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 | maxRateTimerCallback (const ros::TimerEvent &) |
void | signalFailure (const MEvent &evt, FilterFailureReason reason) |
bool | testMessage (const MEvent &evt) |
void | testMessages () |
void | transformsChanged () |
Private Attributes | |
uint64_t | dropped_message_count_ |
uint64_t | failed_out_the_back_count_ |
uint64_t | failed_transform_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_ |
ros::Duration | max_rate_ |
ros::Timer | max_rate_timer_ |
message_filters::Connection | message_connection_ |
uint32_t | message_count_ |
The number of messages in the list. Used because messages_.size() has linear cost. | |
L_Event | messages_ |
The message list. | |
boost::mutex | messages_mutex_ |
The mutex used for locking message list operations. | |
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 | nh_ |
The node used to subscribe to the topic. | |
uint32_t | queue_size_ |
The maximum number of messages we queue up. | |
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. | |
boost::signals2::connection | tf_connection_ |
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_ |
bool | warned_about_unresolved_name_ |
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.
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 106 of file message_filter.h.
typedef boost::function<void(const MConstPtr&, FilterFailureReason)> tf::MessageFilter< M >::FailureCallback |
Definition at line 111 of file message_filter.h.
typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> tf::MessageFilter< M >::FailureSignal |
Definition at line 112 of file message_filter.h.
typedef std::list<MEvent> tf::MessageFilter< M >::L_Event [private] |
Definition at line 339 of file message_filter.h.
typedef boost::shared_ptr<M const> tf::MessageFilter< M >::MConstPtr |
Reimplemented from message_filters::SimpleFilter< M >.
Definition at line 109 of file message_filter.h.
typedef ros::MessageEvent<M const> tf::MessageFilter< M >::MEvent |
Definition at line 110 of file message_filter.h.
tf::MessageFilter< M >::MessageFilter | ( | Transformer & | tf, |
const std::string & | target_frame, | ||
uint32_t | queue_size, | ||
ros::NodeHandle | nh = ros::NodeHandle() , |
||
ros::Duration | max_rate = ros::Duration(0.01) |
||
) | [inline] |
Constructor.
tf | The tf::Transformer this filter should use |
target_frame | The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. |
queue_size | The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). |
nh | The NodeHandle to use for any necessary operations |
max_rate | The maximum rate to check for newly transformable messages |
Definition at line 123 of file message_filter.h.
tf::MessageFilter< M >::MessageFilter | ( | F & | f, |
Transformer & | tf, | ||
const std::string & | target_frame, | ||
uint32_t | queue_size, | ||
ros::NodeHandle | nh = ros::NodeHandle() , |
||
ros::Duration | max_rate = ros::Duration(0.01) |
||
) | [inline] |
Constructor.
f | The filter to connect this filter's input to. Often will be a message_filters::Subscriber. |
tf | The tf::Transformer this filter should use |
target_frame | The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. |
queue_size | The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). |
nh | The NodeHandle to use for any necessary operations |
max_rate | The maximum rate to check for newly transformable messages |
Definition at line 145 of file message_filter.h.
tf::MessageFilter< M >::~MessageFilter | ( | ) | [inline] |
Destructor.
Definition at line 171 of file message_filter.h.
void tf::MessageFilter< M >::add | ( | const MEvent & | evt | ) | [inline] |
Definition at line 247 of file message_filter.h.
void tf::MessageFilter< M >::add | ( | const MConstPtr & | message | ) | [inline] |
Manually add a message into this filter.
Definition at line 290 of file message_filter.h.
void tf::MessageFilter< M >::checkFailures | ( | ) | [inline, private] |
Definition at line 479 of file message_filter.h.
void tf::MessageFilter< M >::clear | ( | ) | [inline, virtual] |
Clear any messages currently in the queue.
Implements tf::MessageFilterBase.
Definition at line 234 of file message_filter.h.
Connect this filter's input to another filter's output. If this filter is already connected, disconnects first.
Definition at line 162 of file message_filter.h.
void tf::MessageFilter< M >::disconnectFailure | ( | const message_filters::Connection & | c | ) | [inline, private] |
Definition at line 507 of file message_filter.h.
virtual uint32_t tf::MessageFilter< M >::getQueueSize | ( | ) | [inline, virtual] |
Implements tf::MessageFilterBase.
Definition at line 313 of file message_filter.h.
std::string tf::MessageFilter< M >::getTargetFramesString | ( | ) | [inline] |
Get the target frames as a string for debugging.
Definition at line 217 of file message_filter.h.
void tf::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 467 of file message_filter.h.
void tf::MessageFilter< M >::init | ( | ) | [inline, private] |
Definition at line 320 of file message_filter.h.
void tf::MessageFilter< M >::maxRateTimerCallback | ( | const ros::TimerEvent & | ) | [inline, private] |
Definition at line 452 of file message_filter.h.
message_filters::Connection tf::MessageFilter< M >::registerFailureCallback | ( | const FailureCallback & | callback | ) | [inline] |
Register a callback to be called when a message is about to be dropped.
callback | The callback to call |
Definition at line 302 of file message_filter.h.
virtual void tf::MessageFilter< M >::setQueueSize | ( | uint32_t | new_queue_size | ) | [inline, virtual] |
Implements tf::MessageFilterBase.
Definition at line 308 of file message_filter.h.
void tf::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 tf::MessageFilterBase.
Definition at line 190 of file message_filter.h.
void tf::MessageFilter< M >::setTargetFrames | ( | 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::MessageFilterBase.
Definition at line 200 of file message_filter.h.
void tf::MessageFilter< M >::setTolerance | ( | const ros::Duration & | tolerance | ) | [inline, virtual] |
Set the required tolerance for the notifier to return true.
Implements tf::MessageFilterBase.
Definition at line 226 of file message_filter.h.
void tf::MessageFilter< M >::signalFailure | ( | const MEvent & | evt, |
FilterFailureReason | reason | ||
) | [inline, private] |
Definition at line 513 of file message_filter.h.
bool tf::MessageFilter< M >::testMessage | ( | const MEvent & | evt | ) | [inline, private] |
Definition at line 341 of file message_filter.h.
void tf::MessageFilter< M >::testMessages | ( | ) | [inline, private] |
Definition at line 426 of file message_filter.h.
void tf::MessageFilter< M >::transformsChanged | ( | ) | [inline, private] |
Definition at line 472 of file message_filter.h.
uint64_t tf::MessageFilter< M >::dropped_message_count_ [private] |
Definition at line 543 of file message_filter.h.
uint64_t tf::MessageFilter< M >::failed_out_the_back_count_ [private] |
Definition at line 540 of file message_filter.h.
uint64_t tf::MessageFilter< M >::failed_transform_count_ [private] |
Definition at line 539 of file message_filter.h.
FailureSignal tf::MessageFilter< M >::failure_signal_ [private] |
Definition at line 555 of file message_filter.h.
boost::mutex tf::MessageFilter< M >::failure_signal_mutex_ [private] |
Definition at line 556 of file message_filter.h.
uint64_t tf::MessageFilter< M >::incoming_message_count_ [private] |
Definition at line 542 of file message_filter.h.
std::string tf::MessageFilter< M >::last_out_the_back_frame_ [private] |
Definition at line 546 of file message_filter.h.
ros::Time tf::MessageFilter< M >::last_out_the_back_stamp_ [private] |
Definition at line 545 of file message_filter.h.
ros::Duration tf::MessageFilter< M >::max_rate_ [private] |
Definition at line 521 of file message_filter.h.
ros::Timer tf::MessageFilter< M >::max_rate_timer_ [private] |
Definition at line 522 of file message_filter.h.
message_filters::Connection tf::MessageFilter< M >::message_connection_ [private] |
Definition at line 553 of file message_filter.h.
uint32_t tf::MessageFilter< M >::message_count_ [private] |
The number of messages in the list. Used because messages_.size() has linear cost.
Definition at line 529 of file message_filter.h.
L_Event tf::MessageFilter< M >::messages_ [private] |
The message list.
Definition at line 528 of file message_filter.h.
boost::mutex tf::MessageFilter< M >::messages_mutex_ [private] |
The mutex used for locking message list operations.
Definition at line 530 of file message_filter.h.
bool tf::MessageFilter< M >::new_messages_ [private] |
Used to skip waiting on new_data_ if new messages have come in while calling back.
Definition at line 532 of file message_filter.h.
volatile bool tf::MessageFilter< M >::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 533 of file message_filter.h.
ros::Time tf::MessageFilter< M >::next_failure_warning_ [private] |
Definition at line 548 of file message_filter.h.
ros::NodeHandle tf::MessageFilter< M >::nh_ [private] |
The node used to subscribe to the topic.
Definition at line 520 of file message_filter.h.
uint32_t tf::MessageFilter< M >::queue_size_ [private] |
The maximum number of messages we queue up.
Definition at line 526 of file message_filter.h.
uint64_t tf::MessageFilter< M >::successful_transform_count_ [private] |
Definition at line 538 of file message_filter.h.
std::vector<std::string> tf::MessageFilter< M >::target_frames_ [private] |
The frames we need to be able to transform to before a message is ready.
Definition at line 523 of file message_filter.h.
std::string tf::MessageFilter< M >::target_frames_string_ [private] |
Definition at line 524 of file message_filter.h.
boost::mutex tf::MessageFilter< M >::target_frames_string_mutex_ [private] |
Definition at line 525 of file message_filter.h.
Transformer& tf::MessageFilter< M >::tf_ [private] |
The Transformer used to determine if transformation data is available.
Definition at line 519 of file message_filter.h.
boost::signals2::connection tf::MessageFilter< M >::tf_connection_ [private] |
Definition at line 552 of file message_filter.h.
ros::Duration tf::MessageFilter< M >::time_tolerance_ [private] |
Provide additional tolerance on time for messages which are stamped but can have associated duration.
Definition at line 550 of file message_filter.h.
uint64_t tf::MessageFilter< M >::transform_message_count_ [private] |
Definition at line 541 of file message_filter.h.
bool tf::MessageFilter< M >::warned_about_empty_frame_id_ [private] |
Definition at line 536 of file message_filter.h.
bool tf::MessageFilter< M >::warned_about_unresolved_name_ [private] |
Definition at line 535 of file message_filter.h.