Go to the documentation of this file.
32 #ifndef TF2_ROS_MESSAGE_FILTER_H
33 #define TF2_ROS_MESSAGE_FILTER_H
40 #include <boost/function.hpp>
41 #include <boost/bind/bind.hpp>
42 #include <boost/shared_ptr.hpp>
43 #include <boost/thread.hpp>
52 #define TF2_ROS_MESSAGEFILTER_DEBUG(fmt, ...) \
53 ROS_DEBUG_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)
55 #define TF2_ROS_MESSAGEFILTER_WARN(fmt, ...) \
56 ROS_WARN_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__)
61 namespace filter_failure_reasons
81 virtual void clear() = 0;
221 TF2_ROS_MESSAGEFILTER_DEBUG(
"Successful Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
234 frames.push_back(target_frame);
246 std::transform(target_frames.begin(), target_frames.end(),
target_frames_.begin(), this->stripSlash);
249 std::stringstream ss;
280 boost::unique_lock< boost::shared_mutex > unique_lock(
messages_mutex_);
306 std::string frame_id =
stripSlash(mt::FrameId<M>::value(*message));
307 ros::Time stamp = mt::TimeStamp<M>::value(*message);
309 if (frame_id.empty())
326 V_string::iterator it = target_frames_copy.begin();
327 V_string::iterator end = target_frames_copy.end();
328 for (; it != end; ++it)
330 const std::string& target_frame = *it;
332 if (handle == 0xffffffffffffffffULL)
337 else if (handle == 0)
343 info.
handles.push_back(handle);
349 if (handle == 0xffffffffffffffffULL)
354 else if (handle == 0)
360 info.
handles.push_back(handle);
374 boost::unique_lock< boost::shared_mutex > unique_lock(
messages_mutex_);
383 V_TransformableRequestHandle::const_iterator it = front.
handles.begin();
384 V_TransformableRequestHandle::const_iterator end = front.
handles.end();
386 for (; it != end; ++it)
415 (*header)[
"callerid"] =
"unknown";
467 typename L_MessageInfo::iterator msg_it =
messages_.begin();
468 typename L_MessageInfo::iterator msg_end =
messages_.end();
469 for (; msg_it != msg_end; ++msg_it)
472 V_TransformableRequestHandle::const_iterator handle_it = std::find(info.
handles.begin(), info.
handles.end(), request_handle);
473 if (handle_it != info.
handles.end())
481 if (msg_it == msg_end)
492 bool can_transform =
true;
494 std::string frame_id =
stripSlash(mt::FrameId<M>::value(*message));
495 ros::Time stamp = mt::TimeStamp<M>::value(*message);
503 for (; it != end; ++it)
505 const std::string& target = *it;
508 can_transform =
false;
516 can_transform =
false;
524 can_transform =
false;
528 boost::upgrade_to_unique_lock< boost::shared_mutex > uniqueLock(lock);
573 if (dropped_pct > 0.95)
658 if ( !in.empty() && (in[0] ==
'/'))
660 std::string out = in;
boost::signals2::connection getBoostConnection() const
void signalFailure(const MEvent &evt, FilterFailureReason reason)
tf2::BufferCore & bc_
The Transformer used to determine if transformation data is available.
std::string last_out_the_back_frame_
MessageFilter(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.
Follows the patterns set by the message_filters package to implement a filter which only passes messa...
void messageDropped(const MEvent &evt, FilterFailureReason reason)
V_string target_frames_
The frames we need to be able to transform to before a message is ready.
ros::CallbackQueueInterface * callback_queue_
MessageFilter(F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
Constructor.
TransformableCallbackHandle addTransformableCallback(const TransformableCallback &cb)
~MessageFilter()
Destructor.
tf2::TransformableCallbackHandle callback_handle_
boost::mutex failure_signal_mutex_
boost::shared_ptr< M const > MConstPtr
boost::shared_mutex messages_mutex_
The mutex used for locking message list operations.
void disconnectFailure(const message_filters::Connection &c)
static std::string stripSlash(const std::string &in)
CBQueueCallback(MessageFilter *filter, const MEvent &event, bool success, FilterFailureReason reason)
boost::mutex target_frames_mutex_
A mutex to protect access to the target_frames_ list and target_frames_string.
virtual uint32_t getQueueSize()
#define TF2_ROS_MESSAGEFILTER_WARN(fmt,...)
MessageFilter(tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
Constructor.
FailureSignal failure_signal_
V_TransformableRequestHandle handles
uint32_t queue_size_
The maximum number of messages we queue up.
void transformable(tf2::TransformableRequestHandle request_handle, const std::string &, const std::string &, ros::Time, tf2::TransformableResult result)
void incomingMessage(const ros::MessageEvent< M const > &evt)
Callback that happens when we receive a message on the message topic.
boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
void clear()
Clear any messages currently in the queue.
ros::Time last_out_the_back_stamp_
uint64_t TransformableRequestHandle
std::string getTargetFramesString()
Get the target frames as a string for debugging.
@ EmptyFrameID
The frame_id on the message is empty.
#define TF2_ROS_MESSAGEFILTER_DEBUG(fmt,...)
void setTolerance(const ros::Duration &tolerance)
Set the required tolerance for the notifier to return true.
@ Unknown
The message buffer overflowed, and this message was pushed off the back of the queue,...
uint32_t expected_success_count_
virtual void removeByID(uint64_t owner_id)=0
virtual void setTolerance(const ros::Duration &tolerance)=0
filter_failure_reasons::FilterFailureReason FilterFailureReason
bool canTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
void setTargetFrame(const std::string &target_frame)
Set the frame you need to be able to transform to before getting a message callback.
void cancelTransformableRequest(TransformableRequestHandle handle)
@ OutTheBack
The timestamp on the message is more than the cache length earlier than the newest data in the transf...
virtual void setQueueSize(uint32_t new_queue_size)
FilterFailureReason reason_
ros::MessageEvent< M const > MEvent
virtual void addCallback(const CallbackInterfacePtr &callback, uint64_t owner_id=0)=0
std::list< MessageInfo > L_MessageInfo
void setTargetFrames(const V_string &target_frames)
Set the frames you need to be able to transform to before getting a message callback.
void connectInput(F &f)
Connect this filter's input to another filter's output. If this filter is already connected,...
bool warned_about_empty_frame_id_
std::vector< std::string > V_string
uint32_t message_count_
The number of messages in the list. Used because <container>.size() may have linear cost.
uint64_t dropped_message_count_
MessageFilter(F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
Constructor.
std::vector< tf2::TransformableRequestHandle > V_TransformableRequestHandle
ros::WallTime next_failure_warning_
TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
virtual ~MessageFilterBase()
void add(const MConstPtr &message)
Manually add a message into this filter.
uint64_t successful_transform_count_
message_filters::Connection message_connection_
std::vector< std::string > V_string
boost::shared_ptr< M > getMessage() const
#define ROSCONSOLE_DEFAULT_NAME
void removeTransformableCallback(TransformableCallbackHandle handle)
uint64_t transform_message_count_
void messageReady(const MEvent &evt)
void signalMessage(const MConstPtr &msg)
virtual void setTargetFrame(const std::string &target_frame)=0
std::string target_frames_string_
void add(const MEvent &evt)
ros::Duration time_tolerance_
Provide additional tolerance on time for messages which are stamped but can have associated duration.
virtual void setTargetFrames(const V_string &target_frames)=0
uint64_t incoming_message_count_
uint32_t TransformableCallbackHandle
uint64_t failed_out_the_back_count_
boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
virtual CallResult call()
tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Apr 25 2025 02:15:51