tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
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 <message_filters/connection.h>
36 #include <message_filters/message_traits.h>
37 #include <message_filters/simple_filter.h>
38 #include <tf2/buffer_core_interface.h>
39 #include <tf2/time.h>
41 #include <tf2_ros/buffer.h>
42 
43 #include <builtin_interfaces/msg/time.hpp>
44 #include <rclcpp/rclcpp.hpp>
45 
46 #include <algorithm>
47 #include <chrono>
48 #include <functional>
49 #include <list>
50 #include <memory>
51 #include <mutex>
52 #include <ratio>
53 #include <sstream>
54 #include <string>
55 #include <tuple>
56 #include <type_traits>
57 #include <vector>
58 
59 #define TF2_ROS_MESSAGEFILTER_DEBUG(fmt, ...) \
60  RCUTILS_LOG_DEBUG_NAMED( \
61  "tf2_ros_message_filter", \
62  std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), \
63  getTargetFramesString().c_str(), __VA_ARGS__)
64 
65 #define TF2_ROS_MESSAGEFILTER_WARN(fmt, ...) \
66  RCUTILS_LOG_WARN_NAMED( \
67  "tf2_ros_message_filter", \
68  std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), \
69  getTargetFramesString().c_str(), __VA_ARGS__)
70 
71 namespace tf2_ros
72 {
73 
74 namespace filter_failure_reasons
75 {
77 {
78  // NOTE when adding new values, do not explicitly assign a number. See FilterFailureReasonCount
79 
81  // reason it was unable to be transformed is unknown.
93 };
94 
95 } // namespace filter_failure_reasons
96 
97 static std::string get_filter_failure_reason_string(
99 {
100  switch (reason) {
102  return
103  "the timestamp on the message is earlier than all the data in the transform cache";
105  return "the frame id of the message is empty";
107  return "did not find a valid transform, this usually happens at startup ...";
109  return "discarding message because the queue is full";
110  case filter_failure_reasons::Unknown: // fallthrough
111  default:
112  return "unknown";
113  }
114 }
115 
117 
119 {
120 public:
122 
123  virtual ~MessageFilterBase() {}
124  virtual void clear() = 0;
125  virtual void setTargetFrame(const std::string & target_frame) = 0;
126  virtual void setTargetFrames(const V_string & target_frames) = 0;
127  virtual void setTolerance(const rclcpp::Duration & tolerance) = 0;
128 };
129 
146 template<class M, class BufferT = tf2_ros::Buffer>
147 class MessageFilter : public MessageFilterBase, public message_filters::SimpleFilter<M>
148 {
149 public:
151  typedef message_filters::MessageEvent<M const> MEvent;
152 
162  template<typename TimeRepT = int64_t, typename TimeT = std::nano>
164  BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
165  const rclcpp::Node::SharedPtr & node,
168  : MessageFilter(buffer, target_frame, queue_size, node->get_node_logging_interface(),
169  node->get_node_clock_interface(), buffer_timeout)
170  {
171  static_assert(
173  "Buffer type must implement tf2::BufferCoreInterface");
174  static_assert(
176  "Buffer type must implement tf2_ros::AsyncBufferInterface");
177  }
178 
189  template<typename TimeRepT = int64_t, typename TimeT = std::nano>
191  BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
192  const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging,
193  const rclcpp::node_interfaces::NodeClockInterface::SharedPtr & node_clock,
196  : node_logging_(node_logging),
197  node_clock_(node_clock),
198  buffer_(buffer),
199  queue_size_(queue_size),
200  buffer_timeout_(buffer_timeout)
201  {
202  init();
203  setTargetFrame(target_frame);
204  }
205 
216  template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
218  F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
219  const rclcpp::Node::SharedPtr & node,
222  : MessageFilter(f, buffer, target_frame, queue_size, node->get_node_logging_interface(),
223  node->get_node_clock_interface(), buffer_timeout)
224  {
225  }
226 
238  template<class F, typename TimeRepT = int64_t, typename TimeT = std::nano>
240  F & f, BufferT & buffer, const std::string & target_frame, uint32_t queue_size,
241  const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & node_logging,
242  const rclcpp::node_interfaces::NodeClockInterface::SharedPtr & node_clock,
245  : node_logging_(node_logging),
246  node_clock_(node_clock),
247  buffer_(buffer),
248  queue_size_(queue_size),
249  buffer_timeout_(buffer_timeout)
250  {
251  init();
252  setTargetFrame(target_frame);
253  connectInput(f);
254  }
255 
259  template<class F>
260  void connectInput(F & f)
261  {
262  message_connection_.disconnect();
263  message_connection_ = f.registerCallback(&MessageFilter::incomingMessage, this);
264  }
265 
270  {
271  message_connection_.disconnect();
272  clear();
273 
275  "Successful Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, "
276  "Messages received: %llu, Total dropped: %llu",
277  static_cast<uint64_t>(successful_transform_count_),
278  static_cast<uint64_t>(failed_out_the_back_count_),
279  static_cast<uint64_t>(transform_message_count_),
280  static_cast<uint64_t>(incoming_message_count_),
281  static_cast<uint64_t>(dropped_message_count_));
282  }
283 
287  void setTargetFrame(const std::string & target_frame)
288  {
289  V_string frames;
290  frames.push_back(target_frame);
291  setTargetFrames(frames);
292  }
293 
297  void setTargetFrames(const V_string & target_frames)
298  {
299  std::unique_lock<std::mutex> frames_lock(target_frames_mutex_);
300 
301  target_frames_.resize(target_frames.size());
303  target_frames.begin(), target_frames.end(),
304  target_frames_.begin(), this->stripSlash);
305  expected_success_count_ = target_frames_.size() * (time_tolerance_.nanoseconds() ? 2 : 1);
306 
308  for (V_string::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it) {
309  ss << *it << " ";
310  }
311  target_frames_string_ = ss.str();
312  }
313 
318  {
319  std::unique_lock<std::mutex> frames_lock(target_frames_mutex_);
320  return target_frames_string_;
321  }
322 
326  void setTolerance(const rclcpp::Duration & tolerance)
327  {
328  std::unique_lock<std::mutex> frames_lock(target_frames_mutex_);
329  time_tolerance_ = tolerance;
330  expected_success_count_ = target_frames_.size() * (time_tolerance_.nanoseconds() ? 2 : 1);
331  }
332 
336  void clear()
337  {
338  std::unique_lock<std::mutex> unique_lock(messages_mutex_);
339 
340  TF2_ROS_MESSAGEFILTER_DEBUG("%s", "Cleared");
341 
342  messages_.clear();
343 
344  warned_about_empty_frame_id_ = false;
345  }
346 
347  void add(const MEvent & evt)
348  {
349  if (target_frames_.empty()) {
350  return;
351  }
352 
353  namespace mt = message_filters::message_traits;
354  const MConstPtr & message = evt.getMessage();
355  std::string frame_id = stripSlash(mt::FrameId<M>::value(*message));
356  rclcpp::Time stamp = mt::TimeStamp<M>::value(*message);
357 
358  if (frame_id.empty()) {
359  messageDropped(evt, filter_failure_reasons::EmptyFrameID);
360  return;
361  }
362 
364  // iterate through the target frames and add requests for each of them
365  MessageInfo info;
366  info.handles.reserve(expected_success_count_);
367  {
368  V_string target_frames_copy;
369  // Copy target_frames_ to avoid deadlock from #79
370  {
371  std::unique_lock<std::mutex> frames_lock(target_frames_mutex_);
372  target_frames_copy = target_frames_;
373  }
374 
375  V_string::iterator it = target_frames_copy.begin();
376  V_string::iterator end = target_frames_copy.end();
377  for (; it != end; ++it) {
378  const std::string & target_frame = *it;
379  wait_params.emplace_back(
380  next_handle_index_, tf2::timeFromSec(stamp.seconds()), target_frame);
381  info.handles.push_back(next_handle_index_++);
382 
383  if (time_tolerance_.nanoseconds()) {
384  wait_params.emplace_back(
385  next_handle_index_,
386  tf2::timeFromSec((stamp + time_tolerance_).seconds()),
387  target_frame);
388  info.handles.push_back(next_handle_index_++);
389  }
390  }
391  }
392 
393  {
394  // Keep a lock on the messages
395  std::unique_lock<std::mutex> unique_lock(messages_mutex_);
396 
397  // If this message is about to push us past our queue size, erase the oldest message
398  if (queue_size_ != 0 && messages_.size() + 1 > queue_size_) {
399  ++dropped_message_count_;
400  const MessageInfo & front = messages_.front();
402  "Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)",
403  messages_.size(),
404  (mt::FrameId<M>::value(*front.event.getMessage())).c_str(),
405  mt::TimeStamp<M>::value(*front.event.getMessage()).seconds());
406 
407  messageDropped(front.event, filter_failure_reasons::QueueFull);
408 
409  messages_.pop_front();
410  }
411 
412  // Add the message to our list
413  info.event = evt;
414  messages_.push_back(info);
415  }
416 
418  "Added message in frame %s at time %.3f, count now %d",
419  frame_id.c_str(), stamp.seconds(), messages_.size());
420  ++incoming_message_count_;
421 
422  for (const auto & param : wait_params) {
423  const auto & handle = std::get<0>(param);
424  const auto & stamp = std::get<1>(param);
425  const auto & target_frame = std::get<2>(param);
426  buffer_.waitForTransform(
427  target_frame,
428  frame_id,
429  stamp,
430  buffer_timeout_,
431  std::bind(&MessageFilter::transformReadyCallback, this, std::placeholders::_1, handle));
432  }
433  }
434 
440  void add(const MConstPtr & message)
441  {
442  builtin_interfaces::msg::Time t = node_clock_->get_clock()->now();
443  add(MEvent(message, t));
444  }
445 
450 #if 0
451  message_filters::Connection registerFailureCallback(const FailureCallback & callback)
452  {
453  message_connection_failure.disconnect();
454  message_connection_failure = this->registerCallback(callback, this);
455  }
456 #endif
457 
458  virtual void setQueueSize(uint32_t new_queue_size)
459  {
460  queue_size_ = new_queue_size;
461  }
462 
463  virtual uint32_t getQueueSize()
464  {
465  return queue_size_;
466  }
467 
468 private:
469  void init()
470  {
471  successful_transform_count_ = 0;
472  failed_out_the_back_count_ = 0;
473  transform_message_count_ = 0;
474  incoming_message_count_ = 0;
475  dropped_message_count_ = 0;
476  time_tolerance_ = rclcpp::Duration(0, 0);
477  warned_about_empty_frame_id_ = false;
478  expected_success_count_ = 1;
479  }
480 
481  void transformReadyCallback(const tf2_ros::TransformStampedFuture & future, const uint64_t handle)
482  {
483  namespace mt = message_filters::message_traits;
484 
485  MEvent saved_event;
486  bool event_found = false;
487 
488  {
489  // We will be accessing and mutating messages now, require unique lock
490  std::unique_lock<std::mutex> lock(messages_mutex_);
491 
492  // find the message this request is associated with
493  typename L_MessageInfo::iterator msg_it = messages_.begin();
494  typename L_MessageInfo::iterator msg_end = messages_.end();
495 
496  for (; msg_it != msg_end; ++msg_it) {
497  MessageInfo & info = *msg_it;
498  auto handle_it = std::find(info.handles.begin(), info.handles.end(), handle);
499  if (handle_it != info.handles.end()) {
500  // found msg_it
501  ++info.success_count;
502  if (info.success_count >= expected_success_count_) {
503  saved_event = msg_it->event;
504  messages_.erase(msg_it);
505  event_found = true;
506  }
507  break;
508  }
509  }
510  }
511 
512  if (!event_found) {
513  return;
514  }
515 
516  bool can_transform = true;
517  const MConstPtr & message = saved_event.getMessage();
518  std::string frame_id = stripSlash(mt::FrameId<M>::value(*message));
519  rclcpp::Time stamp = mt::TimeStamp<M>::value(*message);
520 
521  bool transform_available = true;
523  try {
524  future.get();
525  } catch (...) {
526  transform_available = false;
528  }
529 
530  if (transform_available) {
531  std::unique_lock<std::mutex> frames_lock(target_frames_mutex_);
532  // make sure we can still perform all the necessary transforms
533  typename V_string::iterator it = target_frames_.begin();
534  typename V_string::iterator end = target_frames_.end();
535  for (; it != end; ++it) {
536  const std::string & target = *it;
537  if (!buffer_.canTransform(target, frame_id, tf2::timeFromSec(stamp.seconds()), NULL)) {
538  can_transform = false;
539  break;
540  }
541 
542  if (time_tolerance_.nanoseconds()) {
543  if (!buffer_.canTransform(
544  target, frame_id,
545  tf2::timeFromSec((stamp + time_tolerance_).seconds()), NULL))
546  {
547  can_transform = false;
548  break;
549  }
550  }
551  }
552  } else {
553  can_transform = false;
554  }
555 
556  if (can_transform) {
558  "Message ready in frame %s at time %.3f, count now %d",
559  frame_id.c_str(), stamp.seconds(), messages_.size());
560 
561  ++successful_transform_count_;
562  messageReady(saved_event);
563  } else {
564  ++dropped_message_count_;
565 
567  "Discarding message in frame %s at time %.3f, count now %d",
568  frame_id.c_str(), stamp.seconds(), messages_.size());
569  messageDropped(saved_event, error);
570  }
571  }
572 
576  void incomingMessage(const message_filters::MessageEvent<M const> & evt)
577  {
578  add(evt);
579  }
580 
581  void checkFailures()
582  {
583  if (!next_failure_warning_.nanoseconds()) {
584  next_failure_warning_ = node_clock_->get_clock()->now() + rclcpp::Duration(15, 0);
585  }
586 
587  if (node_clock_->get_clock()->now() >= next_failure_warning_) {
588  if (incoming_message_count_ - messages_.size() == 0) {
589  return;
590  }
591 
592  double dropped_pct = static_cast<double>(dropped_message_count_) /
593  static_cast<double>(incoming_message_count_ - messages_.size());
594  if (dropped_pct > 0.95) {
596  "Dropped %.2f%% of messages so far. Please turn the "
597  "[tf2_ros_message_filter.message_notifier] rosconsole logger to DEBUG for more "
598  "information.",
599  dropped_pct * 100);
600  next_failure_warning_ = node_clock_->get_clock()->now() + rclcpp::Duration(60, 0);
601 
602  if (static_cast<double>(failed_out_the_back_count_) /
603  static_cast<double>(dropped_message_count_) > 0.5)
604  {
606  " The majority of dropped messages were due to messages growing older than the TF "
607  "cache time. The last message's timestamp was: %f, and the last frame_id was: %s",
608  last_out_the_back_stamp_.seconds(), last_out_the_back_frame_.c_str());
609  }
610  }
611  }
612  }
613 
614  // TODO(clalancette): reenable this once we have underlying support for callback queues
615 #if 0
616  struct CBQueueCallback : public ros::CallbackInterface
617  {
618  CBQueueCallback(
619  MessageFilter * filter, const MEvent & event, bool success, FilterFailureReason reason)
620  : event_(event),
621  filter_(filter),
622  reason_(reason),
623  success_(success)
624  {}
625 
626 
627  virtual CallResult call()
628  {
629  if (success_) {
630  filter_->signalMessage(event_);
631  } else {
632  filter_->signalFailure(event_, reason_);
633  }
634 
635  return Success;
636  }
637 
638 private:
639  MEvent event_;
640  MessageFilter * filter_;
641  FilterFailureReason reason_;
642  bool success_;
643  };
644 #endif
645 
646  void messageDropped(const MEvent & evt, FilterFailureReason reason)
647  {
648  // TODO(clalancette): reenable this once we have underlying support for callback queues
649 #if 0
650  if (callback_queue_) {
651  ros::CallbackInterfacePtr cb(new CBQueueCallback(this, evt, false, reason));
652  callback_queue_->addCallback(cb, (uint64_t)this);
653  } else {}
654 #endif
655  {
656  signalFailure(evt, reason);
657  }
658  }
659 
660  void messageReady(const MEvent & evt)
661  {
662  // TODO(clalancette): reenable this once we have underlying support for callback queues
663 #if 0
664  if (callback_queue_) {
665  ros::CallbackInterfacePtr cb(new CBQueueCallback(
666  this, evt, true, filter_failure_reasons::Unknown));
667  callback_queue_->addCallback(cb, (uint64_t)this);
668  } else {}
669 #endif
670  {
671  this->signalMessage(evt);
672  }
673  }
674 
675  void signalFailure(const MEvent & evt, FilterFailureReason reason)
676  {
677  namespace mt = message_filters::message_traits;
678  const MConstPtr & message = evt.getMessage();
679  std::string frame_id = stripSlash(mt::FrameId<M>::value(*message));
680  rclcpp::Time stamp = mt::TimeStamp<M>::value(*message);
681  RCLCPP_INFO(
682  node_logging_->get_logger(),
683  "Message Filter dropping message: frame '%s' at time %.3f for reason '%s'",
684  frame_id.c_str(), stamp.seconds(), get_filter_failure_reason_string(reason).c_str());
685  }
686 
687  static std::string stripSlash(const std::string & in)
688  {
689  if (!in.empty() && (in[0] == '/')) {
690  std::string out = in;
691  out.erase(0, 1);
692  return out;
693  }
694 
695  return in;
696  }
697 
699  const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
701  const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
703  BufferT & buffer_;
705  V_string target_frames_;
706  std::string target_frames_string_;
708  std::mutex target_frames_mutex_;
710  uint32_t queue_size_;
711 
712  uint64_t next_handle_index_ = 0;
713  struct MessageInfo
714  {
715  MessageInfo()
716  : success_count(0) {}
717 
718  MEvent event;
719  std::vector<uint64_t> handles;
720  uint64_t success_count;
721  };
722  typedef std::list<MessageInfo> L_MessageInfo;
723  L_MessageInfo messages_;
724 
726  std::mutex messages_mutex_;
727  uint64_t expected_success_count_;
728 
729  bool warned_about_empty_frame_id_;
730 
731  uint64_t successful_transform_count_;
732  uint64_t failed_out_the_back_count_;
733  uint64_t transform_message_count_;
734  uint64_t incoming_message_count_;
735  uint64_t dropped_message_count_;
736 
737  rclcpp::Time last_out_the_back_stamp_;
738  std::string last_out_the_back_frame_;
739 
740  rclcpp::Time next_failure_warning_;
741 
743  // but can have associated duration
744  rclcpp::Duration time_tolerance_ = rclcpp::Duration(0, 0);
745 
746  message_filters::Connection message_connection_;
747  message_filters::Connection message_connection_failure;
748 
749  // Timeout duration when calling the buffer method 'waitForTransform'
750  tf2::Duration buffer_timeout_;
751 };
752 } // namespace tf2_ros
753 
754 #endif // TF2_ROS__MESSAGE_FILTER_H_
std::shared_future
std::vector::resize
T resize(T... args)
std::bind
T bind(T... args)
std::string
std::shared_ptr
tf2_ros::MessageFilter::MEvent
message_filters::MessageEvent< M const > MEvent
Definition: message_filter.h:151
tf2_ros::MessageFilter
Follows the patterns set by the message_filters package to implement a filter which only passes messa...
Definition: message_filter.h:147
std::list< MessageInfo >
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:297
std::list::pop_front
T pop_front(T... args)
std::vector::reserve
T reserve(T... args)
std::vector
std::find
T find(T... args)
std::vector::size
T size(T... args)
tf2_ros::MessageFilter::MessageFilter
MessageFilter(F &f, BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &node_logging, const rclcpp::node_interfaces::NodeClockInterface::SharedPtr &node_clock, std::chrono::duration< TimeRepT, TimeT > buffer_timeout=std::chrono::duration< TimeRepT, TimeT >::max())
Constructor.
Definition: message_filter.h:239
tf2_ros::filter_failure_reasons::FilterFailureReason
FilterFailureReason
Definition: message_filter.h:76
std::chrono::duration
tf2_ros::filter_failure_reasons::NoTransformFound
@ NoTransformFound
No transform found.
Definition: message_filter.h:88
std::stringstream
std::shared_future::get
T get(T... args)
tf2_ros::MessageFilter::setQueueSize
virtual void setQueueSize(uint32_t new_queue_size)
Register a callback to be called when a message is about to be dropped.
Definition: message_filter.h:458
std::list::front
T front(T... args)
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:260
tf2_ros::MessageFilter::MessageFilter
MessageFilter(BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::Node::SharedPtr &node, std::chrono::duration< TimeRepT, TimeT > buffer_timeout=std::chrono::duration< TimeRepT, TimeT >::max())
Constructor.
Definition: message_filter.h:163
tf2_ros::MessageFilter::getQueueSize
virtual uint32_t getQueueSize()
Definition: message_filter.h:463
std::list::clear
T clear(T... args)
tf2_ros::MessageFilter::MConstPtr
std::shared_ptr< M const > MConstPtr
Definition: message_filter.h:150
std::list::push_back
T push_back(T... args)
TF2_ROS_MESSAGEFILTER_WARN
#define TF2_ROS_MESSAGEFILTER_WARN(fmt,...)
Definition: message_filter.h:65
tf2_ros::MessageFilter::setTolerance
void setTolerance(const rclcpp::Duration &tolerance)
Set the required tolerance for the notifier to return true.
Definition: message_filter.h:326
tf2_ros
Definition: async_buffer_interface.h:43
tf2_ros::MessageFilter::getTargetFramesString
std::string getTargetFramesString()
Get the target frames as a string for debugging.
Definition: message_filter.h:317
tf2_ros::MessageFilterBase
Definition: message_filter.h:118
tf2_ros::MessageFilterBase::setTolerance
virtual void setTolerance(const rclcpp::Duration &tolerance)=0
std::string::c_str
T c_str(T... args)
std::unique_lock
tf2_ros::filter_failure_reasons::FilterFailureReasonCount
@ FilterFailureReasonCount
Max enum value for iteration, keep it at the end of the enum.
Definition: message_filter.h:92
tf2_ros::MessageFilter::~MessageFilter
~MessageFilter()
Destructor.
Definition: message_filter.h:269
tf2_ros::filter_failure_reasons::EmptyFrameID
@ EmptyFrameID
The frame_id on the message is empty.
Definition: message_filter.h:86
TF2_ROS_MESSAGEFILTER_DEBUG
#define TF2_ROS_MESSAGEFILTER_DEBUG(fmt,...)
Definition: message_filter.h:59
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:82
tf2_ros::MessageFilter::add
void add(const MEvent &evt)
Definition: message_filter.h:347
tf2_ros::MessageFilter::MessageFilter
MessageFilter(F &f, BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::Node::SharedPtr &node, std::chrono::duration< TimeRepT, TimeT > buffer_timeout=std::chrono::duration< TimeRepT, TimeT >::max())
Constructor.
Definition: message_filter.h:217
std::list::erase
T erase(T... args)
tf2_ros::MessageFilterBase::clear
virtual void clear()=0
tf2_ros::FilterFailureReason
filter_failure_reasons::FilterFailureReason FilterFailureReason
Definition: message_filter.h:116
tf2_ros::filter_failure_reasons::OutTheBack
@ OutTheBack
The timestamp on the message is earlier than all the data in the transform cache.
Definition: message_filter.h:84
std::transform
T transform(T... args)
buffer.h
tf2_ros::filter_failure_reasons::QueueFull
@ QueueFull
Queue size full.
Definition: message_filter.h:90
std::vector::emplace_back
T emplace_back(T... args)
async_buffer_interface.h
tf2_ros::MessageFilterBase::V_string
std::vector< std::string > V_string
Definition: message_filter.h:121
std::vector::begin
T begin(T... args)
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:287
tf2_ros::MessageFilter::add
void add(const MConstPtr &message)
Manually add a message into this filter.
Definition: message_filter.h:440
tf2_ros::MessageFilterBase::~MessageFilterBase
virtual ~MessageFilterBase()
Definition: message_filter.h:123
std::vector::empty
T empty(T... args)
std::mutex
std::stringstream::str
T str(T... args)
std::vector::end
T end(T... args)
tf2_ros::MessageFilterBase::setTargetFrame
virtual void setTargetFrame(const std::string &target_frame)=0
tf2_ros::MessageFilter::MessageFilter
MessageFilter(BufferT &buffer, const std::string &target_frame, uint32_t queue_size, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &node_logging, const rclcpp::node_interfaces::NodeClockInterface::SharedPtr &node_clock, std::chrono::duration< TimeRepT, TimeT > buffer_timeout=std::chrono::duration< TimeRepT, TimeT >::max())
Constructor.
Definition: message_filter.h:190
tf2_ros::MessageFilter::clear
void clear()
Clear any messages currently in the queue.
Definition: message_filter.h:336
tf2_ros::MessageFilterBase::setTargetFrames
virtual void setTargetFrames(const V_string &target_frames)=0
std::is_base_of