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>
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 |
![]() | |
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 () 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... | |
![]() | |
virtual | ~MessageFilterBase () |
![]() | |
::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< 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, 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) |
Additional Inherited Members | |
![]() | |
::cras::LogHelperPtr | log |
Log helper. More... | |
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); 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.
typedef boost::function<void(const MConstPtr&, tf2_ros::FilterFailureReason)> cras::TfMessageFilter< M, >::FailureCallback |
Definition at line 101 of file message_filter.hpp.
typedef boost::signals2::signal<void(const MConstPtr&, tf2_ros::FilterFailureReason)> cras::TfMessageFilter< M, >::FailureSignal |
Definition at line 102 of file message_filter.hpp.
|
private |
Definition at line 694 of file message_filter.hpp.
typedef boost::shared_ptr<M const> cras::TfMessageFilter< M, >::MConstPtr |
Definition at line 99 of file message_filter.hpp.
typedef ros::MessageEvent<M const> cras::TfMessageFilter< M, >::MEvent |
Definition at line 100 of file message_filter.hpp.
|
private |
Definition at line 683 of file message_filter.hpp.
|
inline |
Constructor.
log | The logger. |
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 114 of file message_filter.hpp.
|
inline |
Constructor.
log | The logger. |
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 135 of file message_filter.hpp.
|
inline |
Constructor.
log | The logger. |
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 158 of file message_filter.hpp.
|
inline |
Constructor.
log | The logger. |
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 181 of file message_filter.hpp.
|
inlineoverride |
Destructor.
Definition at line 207 of file message_filter.hpp.
|
inline |
Manually add a message into this filter.
Definition at line 412 of file message_filter.hpp.
|
inline |
Definition at line 292 of file message_filter.hpp.
|
inlineprivate |
Definition at line 562 of file message_filter.hpp.
|
inlineoverridevirtual |
Clear any messages currently in the queue.
Implements tf2_ros::MessageFilterBase.
Definition at line 271 of file message_filter.hpp.
|
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.
|
inlineprivate |
Definition at line 652 of file message_filter.hpp.
|
inlinevirtual |
Definition at line 437 of file message_filter.hpp.
|
inline |
Get the target frames as a string for debugging.
Definition at line 252 of file message_filter.hpp.
|
inlineprivate |
Callback that happens when we receive a message on the message topic.
Definition at line 557 of file message_filter.hpp.
|
inlineprivate |
Definition at line 443 of file message_filter.hpp.
|
inlineprivate |
Definition at line 626 of file message_filter.hpp.
|
inlineprivate |
Definition at line 639 of file message_filter.hpp.
|
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.hpp.
|
inlinevirtual |
Definition at line 432 of file message_filter.hpp.
|
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.
|
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.
|
inlineoverridevirtual |
Set the required tolerance for the notifier to return true.
Implements tf2_ros::MessageFilterBase.
Definition at line 261 of file message_filter.hpp.
|
inlineprivate |
Definition at line 658 of file message_filter.hpp.
|
inlinestaticprivate |
Definition at line 665 of file message_filter.hpp.
|
inlineprivate |
Definition at line 460 of file message_filter.hpp.
|
private |
The Transformer used to determine if transformation data is available.
Definition at line 676 of file message_filter.hpp.
|
private |
Definition at line 681 of file message_filter.hpp.
|
private |
Definition at line 721 of file message_filter.hpp.
|
private |
Definition at line 706 of file message_filter.hpp.
|
private |
Definition at line 698 of file message_filter.hpp.
|
private |
Definition at line 703 of file message_filter.hpp.
|
private |
Definition at line 718 of file message_filter.hpp.
|
private |
Definition at line 719 of file message_filter.hpp.
|
private |
Definition at line 705 of file message_filter.hpp.
|
private |
Definition at line 709 of file message_filter.hpp.
|
private |
Definition at line 708 of file message_filter.hpp.
|
private |
Definition at line 716 of file message_filter.hpp.
|
private |
The number of messages in the list.
Definition at line 696 of file message_filter.hpp.
|
private |
Definition at line 695 of file message_filter.hpp.
|
private |
The mutex used for locking message list operations.
Definition at line 697 of file message_filter.hpp.
|
private |
Definition at line 711 of file message_filter.hpp.
|
private |
The maximum number of messages we queue up.
Definition at line 680 of file message_filter.hpp.
|
private |
Definition at line 702 of file message_filter.hpp.
|
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.
|
private |
A mutex to protect access to target_frames_ and target_frames_string_.
Definition at line 679 of file message_filter.hpp.
|
private |
Definition at line 678 of file message_filter.hpp.
|
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.
|
private |
Definition at line 704 of file message_filter.hpp.
|
private |
Definition at line 700 of file message_filter.hpp.