message_filter.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_ROS_MESSAGE_FILTER_H
33 #define TF2_ROS_MESSAGE_FILTER_H
34 
35 #include <tf2/buffer_core.h>
36 
37 #include <string>
38 #include <list>
39 #include <vector>
40 #include <boost/function.hpp>
41 #include <boost/bind/bind.hpp>
42 #include <boost/shared_ptr.hpp>
43 #include <boost/thread.hpp>
44 
47 
48 #include <ros/node_handle.h>
50 #include <ros/init.h>
51 
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__)
54 
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__)
57 
58 namespace tf2_ros
59 {
60 
61 namespace filter_failure_reasons
62 {
64 {
71 };
72 }
74 
76 {
77 public:
78  typedef std::vector<std::string> V_string;
79 
80  virtual ~MessageFilterBase(){}
81  virtual void clear() = 0;
82  virtual void setTargetFrame(const std::string& target_frame) = 0;
83  virtual void setTargetFrames(const V_string& target_frames) = 0;
84  virtual void setTolerance(const ros::Duration& tolerance) = 0;
85 };
86 
103 template<class M>
105 {
106 public:
109  typedef boost::function<void(const MConstPtr&, FilterFailureReason)> FailureCallback;
110  typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
111 
112  // If you hit this assert your message does not have a header, or does not have the HasHeader trait defined for it
113  // Actually, we need to check that the message has a header, or that it
114  // has the FrameId and Stamp traits. However I don't know how to do that
115  // so simply commenting out for now.
116  //ROS_STATIC_ASSERT(ros::message_traits::HasHeader<M>::value);
117 
126  MessageFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, const ros::NodeHandle& nh)
127  : bc_(bc)
128  , queue_size_(queue_size)
129  , callback_queue_(nh.getCallbackQueue())
130  {
131  init();
132 
133  setTargetFrame(target_frame);
134  }
135 
145  template<class F>
146  MessageFilter(F& f, tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, const ros::NodeHandle& nh)
147  : bc_(bc)
148  , queue_size_(queue_size)
149  , callback_queue_(nh.getCallbackQueue())
150  {
151  init();
152 
153  setTargetFrame(target_frame);
154 
155  connectInput(f);
156  }
157 
168  MessageFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, ros::CallbackQueueInterface* cbqueue)
169  : bc_(bc)
170  , queue_size_(queue_size)
171  , callback_queue_(cbqueue)
172  {
173  init();
174 
175  setTargetFrame(target_frame);
176  }
177 
189  template<class F>
190  MessageFilter(F& f, tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, ros::CallbackQueueInterface* cbqueue)
191  : bc_(bc)
192  , queue_size_(queue_size)
193  , callback_queue_(cbqueue)
194  {
195  init();
196 
197  setTargetFrame(target_frame);
198 
199  connectInput(f);
200  }
201 
205  template<class F>
206  void connectInput(F& f)
207  {
209  message_connection_ = f.registerCallback(&MessageFilter::incomingMessage, this);
210  }
211 
216  {
218 
220 
221  TF2_ROS_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
222  (long long unsigned int)successful_transform_count_,
223  (long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
224  (long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_);
225 
226  }
227 
231  void setTargetFrame(const std::string& target_frame)
232  {
233  V_string frames;
234  frames.push_back(target_frame);
235  setTargetFrames(frames);
236  }
237 
241  void setTargetFrames(const V_string& target_frames)
242  {
243  boost::mutex::scoped_lock frames_lock(target_frames_mutex_);
244 
245  target_frames_.resize(target_frames.size());
246  std::transform(target_frames.begin(), target_frames.end(), target_frames_.begin(), this->stripSlash);
248 
249  std::stringstream ss;
250  for (V_string::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it)
251  {
252  ss << *it << " ";
253  }
254  target_frames_string_ = ss.str();
255  }
259  std::string getTargetFramesString()
260  {
261  boost::mutex::scoped_lock lock(target_frames_mutex_);
262  return target_frames_string_;
263  };
264 
268  void setTolerance(const ros::Duration& tolerance)
269  {
270  boost::mutex::scoped_lock lock(target_frames_mutex_);
271  time_tolerance_ = tolerance;
273  }
274 
278  void clear()
279  {
280  boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_);
281 
282  TF2_ROS_MESSAGEFILTER_DEBUG("%s", "Cleared");
283 
285  callback_handle_ = bc_.addTransformableCallback(boost::bind(&MessageFilter::transformable, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5));
286 
287  messages_.clear();
288  message_count_ = 0;
289 
290  // remove pending callbacks in callback queue as well
291  if (callback_queue_)
292  callback_queue_->removeByID((uint64_t)this);
293 
295  }
296 
297  void add(const MEvent& evt)
298  {
299  if (target_frames_.empty())
300  {
301  return;
302  }
303 
304  namespace mt = ros::message_traits;
305  const MConstPtr& message = evt.getMessage();
306  std::string frame_id = stripSlash(mt::FrameId<M>::value(*message));
307  ros::Time stamp = mt::TimeStamp<M>::value(*message);
308 
309  if (frame_id.empty())
310  {
312  return;
313  }
314 
315  // iterate through the target frames and add requests for each of them
316  MessageInfo info;
317  info.handles.reserve(expected_success_count_);
318  {
319  V_string target_frames_copy;
320  // Copy target_frames_ to avoid deadlock from #79
321  {
322  boost::mutex::scoped_lock frames_lock(target_frames_mutex_);
323  target_frames_copy = target_frames_;
324  }
325 
326  V_string::iterator it = target_frames_copy.begin();
327  V_string::iterator end = target_frames_copy.end();
328  for (; it != end; ++it)
329  {
330  const std::string& target_frame = *it;
331  tf2::TransformableRequestHandle handle = bc_.addTransformableRequest(callback_handle_, target_frame, frame_id, stamp);
332  if (handle == 0xffffffffffffffffULL) // never transformable
333  {
335  return;
336  }
337  else if (handle == 0)
338  {
339  ++info.success_count;
340  }
341  else
342  {
343  info.handles.push_back(handle);
344  }
345 
346  if (!time_tolerance_.isZero())
347  {
348  handle = bc_.addTransformableRequest(callback_handle_, target_frame, frame_id, stamp + time_tolerance_);
349  if (handle == 0xffffffffffffffffULL) // never transformable
350  {
352  return;
353  }
354  else if (handle == 0)
355  {
356  ++info.success_count;
357  }
358  else
359  {
360  info.handles.push_back(handle);
361  }
362  }
363  }
364  }
365 
366 
367  // We can transform already
369  {
370  messageReady(evt);
371  }
372  else
373  {
374  boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_);
375  // If this message is about to push us past our queue size, erase the oldest message
376  if (queue_size_ != 0 && message_count_ + 1 > queue_size_)
377  {
379  const MessageInfo& front = messages_.front();
380  TF2_ROS_MESSAGEFILTER_DEBUG("Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)", message_count_,
381  (mt::FrameId<M>::value(*front.event.getMessage())).c_str(), mt::TimeStamp<M>::value(*front.event.getMessage()).toSec());
382 
383  V_TransformableRequestHandle::const_iterator it = front.handles.begin();
384  V_TransformableRequestHandle::const_iterator end = front.handles.end();
385 
386  for (; it != end; ++it)
387  {
389  }
390 
392  messages_.pop_front();
393  --message_count_;
394  }
395 
396  // Add the message to our list
397  info.event = evt;
398  messages_.push_back(info);
399  ++message_count_;
400  }
401 
402  TF2_ROS_MESSAGEFILTER_DEBUG("Added message in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_);
403 
405  }
406 
412  void add(const MConstPtr& message)
413  {
414  boost::shared_ptr<std::map<std::string, std::string> > header(new std::map<std::string, std::string>);
415  (*header)["callerid"] = "unknown";
417  ros::Time t(n.sec, n.nsec);
418  add(MEvent(message, header, t));
419  }
420 
426  {
427  boost::mutex::scoped_lock lock(failure_signal_mutex_);
428  return message_filters::Connection(boost::bind(&MessageFilter::disconnectFailure, this, boost::placeholders::_1), failure_signal_.connect(callback));
429  }
430 
431  virtual void setQueueSize( uint32_t new_queue_size )
432  {
433  queue_size_ = new_queue_size;
434  }
435 
436  virtual uint32_t getQueueSize()
437  {
438  return queue_size_;
439  }
440 
441 
442 private:
443 
444  void init()
445  {
446  message_count_ = 0;
455 
456  callback_handle_ = bc_.addTransformableCallback(boost::bind(&MessageFilter::transformable, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5));
457  }
458 
459  void transformable(tf2::TransformableRequestHandle request_handle, const std::string& /* target_frame */, const std::string& /* source_frame */,
460  ros::Time /* time */, tf2::TransformableResult result)
461  {
462  namespace mt = ros::message_traits;
463 
464  boost::upgrade_lock< boost::shared_mutex > lock(messages_mutex_);
465 
466  // find the message this request is associated with
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)
470  {
471  MessageInfo& info = *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())
474  {
475  // found msg_it
476  ++info.success_count;
477  break;
478  }
479  }
480 
481  if (msg_it == msg_end)
482  {
483  return;
484  }
485 
486  const MessageInfo& info = *msg_it;
488  {
489  return;
490  }
491 
492  bool can_transform = true;
493  const MConstPtr& message = info.event.getMessage();
494  std::string frame_id = stripSlash(mt::FrameId<M>::value(*message));
495  ros::Time stamp = mt::TimeStamp<M>::value(*message);
496 
497  if (result == tf2::TransformAvailable)
498  {
499  boost::mutex::scoped_lock frames_lock(target_frames_mutex_);
500  // make sure we can still perform all the necessary transforms
501  typename V_string::iterator it = target_frames_.begin();
502  typename V_string::iterator end = target_frames_.end();
503  for (; it != end; ++it)
504  {
505  const std::string& target = *it;
506  if (!bc_.canTransform(target, frame_id, stamp))
507  {
508  can_transform = false;
509  break;
510  }
511 
512  if (!time_tolerance_.isZero())
513  {
514  if (!bc_.canTransform(target, frame_id, stamp + time_tolerance_))
515  {
516  can_transform = false;
517  break;
518  }
519  }
520  }
521  }
522  else
523  {
524  can_transform = false;
525  }
526 
527  // We will be mutating messages now, require unique lock
528  boost::upgrade_to_unique_lock< boost::shared_mutex > uniqueLock(lock);
529  if (can_transform)
530  {
531  TF2_ROS_MESSAGEFILTER_DEBUG("Message ready in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_ - 1);
532 
534 
535  messageReady(info.event);
536 
537  }
538  else
539  {
541 
542  TF2_ROS_MESSAGEFILTER_DEBUG("Discarding message in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_ - 1);
544  }
545 
546  messages_.erase(msg_it);
547  --message_count_;
548  }
549 
554  {
555  add(evt);
556  }
557 
559  {
561  {
563  }
564 
566  {
568  {
569  return;
570  }
571 
572  double dropped_pct = (double)dropped_message_count_ / (double)(incoming_message_count_ - message_count_);
573  if (dropped_pct > 0.95)
574  {
575  TF2_ROS_MESSAGEFILTER_WARN("Dropped %.2f%% of messages so far. Please turn the [%s.message_notifier] rosconsole logger to DEBUG for more information.", dropped_pct*100, ROSCONSOLE_DEFAULT_NAME);
577 
578  if ((double)failed_out_the_back_count_ / (double)dropped_message_count_ > 0.5)
579  {
580  TF2_ROS_MESSAGEFILTER_WARN(" The majority of dropped messages were due to messages growing older than the TF cache time. The last message's timestamp was: %f, and the last frame_id was: %s", last_out_the_back_stamp_.toSec(), last_out_the_back_frame_.c_str());
581  }
582  }
583  }
584  }
585 
587  {
588  CBQueueCallback(MessageFilter* filter, const MEvent& event, bool success, FilterFailureReason reason)
589  : event_(event)
590  , filter_(filter)
591  , reason_(reason)
592  , success_(success)
593  {}
594 
595 
596  virtual CallResult call()
597  {
598  if (success_)
599  {
601  }
602  else
603  {
605  }
606 
607  return Success;
608  }
609 
610  private:
614  bool success_;
615  };
616 
617  void messageDropped(const MEvent& evt, FilterFailureReason reason)
618  {
619  if (callback_queue_)
620  {
621  ros::CallbackInterfacePtr cb(new CBQueueCallback(this, evt, false, reason));
622  callback_queue_->addCallback(cb, (uint64_t)this);
623  }
624  else
625  {
626  signalFailure(evt, reason);
627  }
628  }
629 
630  void messageReady(const MEvent& evt)
631  {
632  if (callback_queue_)
633  {
635  callback_queue_->addCallback(cb, (uint64_t)this);
636  }
637  else
638  {
639  this->signalMessage(evt);
640  }
641  }
642 
644  {
645  boost::mutex::scoped_lock lock(failure_signal_mutex_);
646  c.getBoostConnection().disconnect();
647  }
648 
649  void signalFailure(const MEvent& evt, FilterFailureReason reason)
650  {
651  boost::mutex::scoped_lock lock(failure_signal_mutex_);
652  failure_signal_(evt.getMessage(), reason);
653  }
654 
655  static
656  std::string stripSlash(const std::string& in)
657  {
658  if ( !in.empty() && (in[0] == '/'))
659  {
660  std::string out = in;
661  out.erase(0, 1);
662  return out;
663  }
664  return in;
665  }
666 
670  boost::mutex target_frames_mutex_;
671  uint32_t queue_size_;
673 
674  typedef std::vector<tf2::TransformableRequestHandle> V_TransformableRequestHandle;
675  struct MessageInfo
676  {
678  : success_count(0)
679  {}
680 
683  uint32_t success_count;
684  };
685  typedef std::list<MessageInfo> L_MessageInfo;
687  uint32_t message_count_;
688  boost::shared_mutex messages_mutex_;
690 
692 
698 
701 
703 
705 
707 
709  boost::mutex failure_signal_mutex_;
710 
712 };
713 
714 } // namespace tf2
715 
716 #endif
tf2_ros::MessageFilter::CBQueueCallback
Definition: message_filter.h:586
simple_filter.h
message_filters::Connection::getBoostConnection
boost::signals2::connection getBoostConnection() const
node_handle.h
tf2_ros::MessageFilter::signalFailure
void signalFailure(const MEvent &evt, FilterFailureReason reason)
Definition: message_filter.h:649
tf2_ros::MessageFilter::bc_
tf2::BufferCore & bc_
The Transformer used to determine if transformation data is available.
Definition: message_filter.h:667
tf2_ros::MessageFilter::last_out_the_back_frame_
std::string last_out_the_back_frame_
Definition: message_filter.h:700
tf2_ros::MessageFilter::MessageFilter
MessageFilter(tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
Constructor.
Definition: message_filter.h:168
tf2_ros::MessageFilter::registerFailureCallback
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
Register a callback to be called when a message is about to be dropped.
Definition: message_filter.h:425
tf2_ros::MessageFilter
Follows the patterns set by the message_filters package to implement a filter which only passes messa...
Definition: message_filter.h:104
message_filters::Connection
tf2_ros::MessageFilter::messageDropped
void messageDropped(const MEvent &evt, FilterFailureReason reason)
Definition: message_filter.h:617
boost::shared_ptr
tf2_ros::MessageFilter::MessageInfo::event
MEvent event
Definition: message_filter.h:681
tf2_ros::MessageFilter::target_frames_
V_string target_frames_
The frames we need to be able to transform to before a message is ready.
Definition: message_filter.h:668
tf2_ros::MessageFilter::callback_queue_
ros::CallbackQueueInterface * callback_queue_
Definition: message_filter.h:711
tf2_ros::MessageFilter::MessageFilter
MessageFilter(F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, ros::CallbackQueueInterface *cbqueue)
Constructor.
Definition: message_filter.h:190
tf2::BufferCore::addTransformableCallback
TransformableCallbackHandle addTransformableCallback(const TransformableCallback &cb)
tf2_ros::MessageFilter::init
void init()
Definition: message_filter.h:444
tf2_ros::MessageFilter::~MessageFilter
~MessageFilter()
Destructor.
Definition: message_filter.h:215
callback_queue_interface.h
tf2_ros::filter_failure_reasons::FilterFailureReason
FilterFailureReason
Definition: message_filter.h:63
tf2_ros::MessageFilter::callback_handle_
tf2::TransformableCallbackHandle callback_handle_
Definition: message_filter.h:672
tf2_ros::MessageFilter::failure_signal_mutex_
boost::mutex failure_signal_mutex_
Definition: message_filter.h:709
tf2_ros::MessageFilter::MConstPtr
boost::shared_ptr< M const > MConstPtr
Definition: message_filter.h:107
init.h
TimeBase< Time, Duration >::toSec
double toSec() const
tf2_ros::MessageFilter::messages_mutex_
boost::shared_mutex messages_mutex_
The mutex used for locking message list operations.
Definition: message_filter.h:688
tf2_ros::MessageFilter::disconnectFailure
void disconnectFailure(const message_filters::Connection &c)
Definition: message_filter.h:643
tf2_ros::MessageFilter::stripSlash
static std::string stripSlash(const std::string &in)
Definition: message_filter.h:656
tf2_ros::MessageFilter::CBQueueCallback::CBQueueCallback
CBQueueCallback(MessageFilter *filter, const MEvent &event, bool success, FilterFailureReason reason)
Definition: message_filter.h:588
tf2_ros::MessageFilter::CBQueueCallback::event_
MEvent event_
Definition: message_filter.h:611
tf2_ros::MessageFilter::target_frames_mutex_
boost::mutex target_frames_mutex_
A mutex to protect access to the target_frames_ list and target_frames_string.
Definition: message_filter.h:670
tf2_ros::MessageFilter::MessageInfo::success_count
uint32_t success_count
Definition: message_filter.h:683
tf2_ros::MessageFilter::getQueueSize
virtual uint32_t getQueueSize()
Definition: message_filter.h:436
ros::message_traits
ros::CallbackInterface::CallResult
CallResult
f
f
TF2_ROS_MESSAGEFILTER_WARN
#define TF2_ROS_MESSAGEFILTER_WARN(fmt,...)
Definition: message_filter.h:55
tf2_ros::MessageFilter::MessageFilter
MessageFilter(tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
Constructor.
Definition: message_filter.h:126
tf2_ros::MessageFilter::failure_signal_
FailureSignal failure_signal_
Definition: message_filter.h:708
message_filters::SimpleFilter
tf2_ros::MessageFilter::MessageInfo::handles
V_TransformableRequestHandle handles
Definition: message_filter.h:682
tf2_ros::MessageFilter::queue_size_
uint32_t queue_size_
The maximum number of messages we queue up.
Definition: message_filter.h:671
tf2_ros::MessageFilter::transformable
void transformable(tf2::TransformableRequestHandle request_handle, const std::string &, const std::string &, ros::Time, tf2::TransformableResult result)
Definition: message_filter.h:459
tf2_ros::MessageFilter::incomingMessage
void incomingMessage(const ros::MessageEvent< M const > &evt)
Callback that happens when we receive a message on the message topic.
Definition: message_filter.h:553
tf2_ros::MessageFilter::FailureSignal
boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
Definition: message_filter.h:110
tf2_ros::MessageFilter::clear
void clear()
Clear any messages currently in the queue.
Definition: message_filter.h:278
tf2_ros
Definition: buffer.h:42
TimeBase< WallTime, WallDuration >::isZero
bool isZero() const
tf2_ros::MessageFilterBase
Definition: message_filter.h:75
tf2_ros::MessageFilter::messages_
L_MessageInfo messages_
Definition: message_filter.h:686
ros::WallTime::now
static WallTime now()
tf2_ros::MessageFilter::last_out_the_back_stamp_
ros::Time last_out_the_back_stamp_
Definition: message_filter.h:699
tf2_ros::MessageFilter::checkFailures
void checkFailures()
Definition: message_filter.h:558
tf2::TransformableRequestHandle
uint64_t TransformableRequestHandle
tf2_ros::MessageFilter::getTargetFramesString
std::string getTargetFramesString()
Get the target frames as a string for debugging.
Definition: message_filter.h:259
tf2_ros::filter_failure_reasons::EmptyFrameID
@ EmptyFrameID
The frame_id on the message is empty.
Definition: message_filter.h:70
TF2_ROS_MESSAGEFILTER_DEBUG
#define TF2_ROS_MESSAGEFILTER_DEBUG(fmt,...)
Definition: message_filter.h:52
tf2_ros::MessageFilter::setTolerance
void setTolerance(const ros::Duration &tolerance)
Set the required tolerance for the notifier to return true.
Definition: message_filter.h:268
tf2_ros::MessageFilter::CBQueueCallback::filter_
MessageFilter * filter_
Definition: message_filter.h:612
tf2_ros::filter_failure_reasons::Unknown
@ Unknown
The message buffer overflowed, and this message was pushed off the back of the queue,...
Definition: message_filter.h:66
tf2_ros::MessageFilter::expected_success_count_
uint32_t expected_success_count_
Definition: message_filter.h:689
ros::CallbackQueueInterface::removeByID
virtual void removeByID(uint64_t owner_id)=0
tf2_ros::MessageFilterBase::setTolerance
virtual void setTolerance(const ros::Duration &tolerance)=0
tf2_ros::MessageFilterBase::clear
virtual void clear()=0
tf2_ros::FilterFailureReason
filter_failure_reasons::FilterFailureReason FilterFailureReason
Definition: message_filter.h:73
tf2::BufferCore::canTransform
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
tf2_ros::MessageFilter::setTargetFrame
void setTargetFrame(const std::string &target_frame)
Set the frame you need to be able to transform to before getting a message callback.
Definition: message_filter.h:231
buffer_core.h
ros::CallbackInterface
tf2::BufferCore::cancelTransformableRequest
void cancelTransformableRequest(TransformableRequestHandle handle)
tf2_ros::filter_failure_reasons::OutTheBack
@ OutTheBack
The timestamp on the message is more than the cache length earlier than the newest data in the transf...
Definition: message_filter.h:68
ros::WallTime
tf2_ros::MessageFilter::setQueueSize
virtual void setQueueSize(uint32_t new_queue_size)
Definition: message_filter.h:431
tf2_ros::MessageFilter::CBQueueCallback::reason_
FilterFailureReason reason_
Definition: message_filter.h:613
ros::CallbackInterface::Success
Success
TimeBase< WallTime, WallDuration >::sec
uint32_t sec
tf2_ros::MessageFilter::MEvent
ros::MessageEvent< M const > MEvent
Definition: message_filter.h:108
TimeBase< WallTime, WallDuration >::nsec
uint32_t nsec
ros::CallbackQueueInterface::addCallback
virtual void addCallback(const CallbackInterfacePtr &callback, uint64_t owner_id=0)=0
tf2_ros::MessageFilter::L_MessageInfo
std::list< MessageInfo > L_MessageInfo
Definition: message_filter.h:685
tf2_ros::MessageFilter::setTargetFrames
void setTargetFrames(const V_string &target_frames)
Set the frames you need to be able to transform to before getting a message callback.
Definition: message_filter.h:241
tf2_ros::MessageFilter::connectInput
void connectInput(F &f)
Connect this filter's input to another filter's output. If this filter is already connected,...
Definition: message_filter.h:206
tf2_ros::MessageFilter::warned_about_empty_frame_id_
bool warned_about_empty_frame_id_
Definition: message_filter.h:691
tf2_ros::MessageFilter::CBQueueCallback::success_
bool success_
Definition: message_filter.h:614
connection.h
tf2_ros::MessageFilterBase::V_string
std::vector< std::string > V_string
Definition: message_filter.h:78
tf2_ros::MessageFilter::message_count_
uint32_t message_count_
The number of messages in the list. Used because <container>.size() may have linear cost.
Definition: message_filter.h:687
tf2_ros::MessageFilter::dropped_message_count_
uint64_t dropped_message_count_
Definition: message_filter.h:697
tf2_ros::MessageFilter::MessageFilter
MessageFilter(F &f, tf2::BufferCore &bc, const std::string &target_frame, uint32_t queue_size, const ros::NodeHandle &nh)
Constructor.
Definition: message_filter.h:146
ros::Time
tf2_ros::MessageFilter::V_TransformableRequestHandle
std::vector< tf2::TransformableRequestHandle > V_TransformableRequestHandle
Definition: message_filter.h:674
tf2::BufferCore
tf2_ros::MessageFilter::next_failure_warning_
ros::WallTime next_failure_warning_
Definition: message_filter.h:702
tf2::BufferCore::addTransformableRequest
TransformableRequestHandle addTransformableRequest(TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
tf2_ros::MessageFilter::MessageInfo
Definition: message_filter.h:675
tf2_ros::MessageFilterBase::~MessageFilterBase
virtual ~MessageFilterBase()
Definition: message_filter.h:80
tf2_ros::MessageFilter::add
void add(const MConstPtr &message)
Manually add a message into this filter.
Definition: message_filter.h:412
tf2_ros::MessageFilter::successful_transform_count_
uint64_t successful_transform_count_
Definition: message_filter.h:693
tf2_ros::MessageFilter::message_connection_
message_filters::Connection message_connection_
Definition: message_filter.h:706
V_string
std::vector< std::string > V_string
ros::MessageEvent::getMessage
boost::shared_ptr< M > getMessage() const
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
tf2::BufferCore::removeTransformableCallback
void removeTransformableCallback(TransformableCallbackHandle handle)
ros::WallDuration
header
const std::string header
tf2_ros::MessageFilter::transform_message_count_
uint64_t transform_message_count_
Definition: message_filter.h:695
tf2_ros::MessageFilter::messageReady
void messageReady(const MEvent &evt)
Definition: message_filter.h:630
message_filters::SimpleFilter::signalMessage
void signalMessage(const MConstPtr &msg)
tf2_ros::MessageFilterBase::setTargetFrame
virtual void setTargetFrame(const std::string &target_frame)=0
tf2_ros::MessageFilter::target_frames_string_
std::string target_frames_string_
Definition: message_filter.h:669
ros::Duration
tf2::TransformableResult
TransformableResult
tf2_ros::MessageFilter::MessageInfo::MessageInfo
MessageInfo()
Definition: message_filter.h:677
tf2_ros::MessageFilter::add
void add(const MEvent &evt)
Definition: message_filter.h:297
ros::CallbackQueueInterface
DurationBase< Duration >::isZero
bool isZero() const
tf2_ros::MessageFilter::time_tolerance_
ros::Duration time_tolerance_
Provide additional tolerance on time for messages which are stamped but can have associated duration.
Definition: message_filter.h:704
tf2_ros::MessageFilterBase::setTargetFrames
virtual void setTargetFrames(const V_string &target_frames)=0
tf2_ros::MessageFilter::incoming_message_count_
uint64_t incoming_message_count_
Definition: message_filter.h:696
ros::NodeHandle
ros::MessageEvent
tf2::TransformableCallbackHandle
uint32_t TransformableCallbackHandle
tf2::TransformAvailable
TransformAvailable
tf2_ros::MessageFilter::failed_out_the_back_count_
uint64_t failed_out_the_back_count_
Definition: message_filter.h:694
tf2_ros::MessageFilter::FailureCallback
boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
Definition: message_filter.h:109
message_filters::Connection::disconnect
void disconnect()
tf2_ros::MessageFilter::CBQueueCallback::call
virtual CallResult call()
Definition: message_filter.h:596


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:16