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>
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 |
![]() | |
typedef std::vector< std::string > | V_string |
Public Member Functions | |
void | add (const MConstPtr &message) |
Manually add a message into this filter. More... | |
void | add (const MEvent &evt) |
void | clear () |
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. If this filter is already connected, disconnects first. More... | |
virtual uint32_t | getQueueSize () |
std::string | getTargetFramesString () |
Get the target frames as a string for debugging. More... | |
template<class F > | |
MessageFilter (F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh) | |
Constructor. More... | |
template<class F > | |
MessageFilter (F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue) | |
Constructor. More... | |
MessageFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh) | |
Constructor. More... | |
MessageFilter (tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue) | |
Constructor. 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) |
Set the frame you need to be able to transform to before getting a message callback. More... | |
void | setTargetFrames (const V_string &target_frames) |
Set the frames you need to be able to transform to before getting a message callback. More... | |
void | setTolerance (const ros::Duration &tolerance) |
Set the required tolerance for the notifier to return true. More... | |
~MessageFilter () | |
Destructor. More... | |
![]() | |
virtual | ~MessageFilterBase () |
Private Types | |
typedef std::list< MessageInfo > | L_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. More... | |
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 &, const std::string &, ros::Time, tf2::TransformableResult result) |
Static Private Member Functions | |
static std::string | stripSlash (const std::string &in) |
Private Attributes | |
tf2::BufferCore & | bc_ |
The Transformer used to determine if transformation data is available. More... | |
tf2::TransformableCallbackHandle | callback_handle_ |
ros::CallbackQueueInterface * | callback_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. 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 the target_frames_ list 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 |
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); tf2_ros::MessageFilter<MessageType> tf_filter(sub, tf_buffer_, "/map", 10, 0); tf_filter.registerCallback(&MyClass::myCallback, this);
Definition at line 104 of file message_filter.h.
typedef boost::function<void(const MConstPtr&, FilterFailureReason)> tf2_ros::MessageFilter< M >::FailureCallback |
Definition at line 109 of file message_filter.h.
typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> tf2_ros::MessageFilter< M >::FailureSignal |
Definition at line 110 of file message_filter.h.
|
private |
Definition at line 685 of file message_filter.h.
typedef boost::shared_ptr<M const> tf2_ros::MessageFilter< M >::MConstPtr |
Definition at line 107 of file message_filter.h.
typedef ros::MessageEvent<M const> tf2_ros::MessageFilter< M >::MEvent |
Definition at line 108 of file message_filter.h.
|
private |
Definition at line 674 of file message_filter.h.
|
inline |
Constructor.
bc | The tf2::BufferCore 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 whose callback queue we should add callbacks to |
Definition at line 126 of file message_filter.h.
|
inline |
Constructor.
f | The filter to connect this filter's input to. Often will be a message_filters::Subscriber. |
bc | The tf2::BufferCore 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 whose callback queue we should add callbacks to |
Definition at line 146 of file message_filter.h.
|
inline |
Constructor.
bc | The tf2::BufferCore 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). |
cbqueue | The 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.
|
inline |
Constructor.
f | The filter to connect this filter's input to. Often will be a message_filters::Subscriber. |
bc | The tf2::BufferCore 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). |
cbqueue | The 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.
|
inline |
Destructor.
Definition at line 215 of file message_filter.h.
|
inline |
Manually add a message into this filter.
Definition at line 412 of file message_filter.h.
|
inline |
Definition at line 297 of file message_filter.h.
|
inlineprivate |
Definition at line 558 of file message_filter.h.
|
inlinevirtual |
Clear any messages currently in the queue.
Implements tf2_ros::MessageFilterBase.
Definition at line 278 of file message_filter.h.
|
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.
|
inlineprivate |
Definition at line 643 of file message_filter.h.
|
inlinevirtual |
Definition at line 436 of file message_filter.h.
|
inline |
Get the target frames as a string for debugging.
Definition at line 259 of file message_filter.h.
|
inlineprivate |
Callback that happens when we receive a message on the message topic.
Definition at line 553 of file message_filter.h.
|
inlineprivate |
Definition at line 444 of file message_filter.h.
|
inlineprivate |
Definition at line 617 of file message_filter.h.
|
inlineprivate |
Definition at line 630 of file message_filter.h.
|
inline |
Register a callback to be called when a message is about to be dropped.
callback | The callback to call |
Definition at line 425 of file message_filter.h.
|
inlinevirtual |
Definition at line 431 of file message_filter.h.
|
inlinevirtual |
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.
|
inlinevirtual |
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.
|
inlinevirtual |
Set the required tolerance for the notifier to return true.
Implements tf2_ros::MessageFilterBase.
Definition at line 268 of file message_filter.h.
|
inlineprivate |
Definition at line 649 of file message_filter.h.
|
inlinestaticprivate |
Definition at line 656 of file message_filter.h.
|
inlineprivate |
Definition at line 459 of file message_filter.h.
|
private |
The Transformer used to determine if transformation data is available.
Definition at line 667 of file message_filter.h.
|
private |
Definition at line 672 of file message_filter.h.
|
private |
Definition at line 711 of file message_filter.h.
|
private |
Definition at line 697 of file message_filter.h.
|
private |
Definition at line 689 of file message_filter.h.
|
private |
Definition at line 694 of file message_filter.h.
|
private |
Definition at line 708 of file message_filter.h.
|
private |
Definition at line 709 of file message_filter.h.
|
private |
Definition at line 696 of file message_filter.h.
|
private |
Definition at line 700 of file message_filter.h.
|
private |
Definition at line 699 of file message_filter.h.
|
private |
Definition at line 706 of file message_filter.h.
|
private |
The number of messages in the list. Used because <container>.size() may have linear cost.
Definition at line 687 of file message_filter.h.
|
private |
Definition at line 686 of file message_filter.h.
|
private |
The mutex used for locking message list operations.
Definition at line 688 of file message_filter.h.
|
private |
Definition at line 702 of file message_filter.h.
|
private |
The maximum number of messages we queue up.
Definition at line 671 of file message_filter.h.
|
private |
Definition at line 693 of file message_filter.h.
|
private |
The frames we need to be able to transform to before a message is ready.
Definition at line 668 of file message_filter.h.
|
private |
A mutex to protect access to the target_frames_ list and target_frames_string.
Definition at line 670 of file message_filter.h.
|
private |
Definition at line 669 of file message_filter.h.
|
private |
Provide additional tolerance on time for messages which are stamped but can have associated duration.
Definition at line 704 of file message_filter.h.
|
private |
Definition at line 695 of file message_filter.h.
|
private |
Definition at line 691 of file message_filter.h.