message_filter.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 TF_MESSAGE_FILTER_H
33 #define TF_MESSAGE_FILTER_H
34 
35 #include <ros/ros.h>
36 #include <tf/transform_listener.h>
37 #include <tf/tfMessage.h>
38 
39 #include <string>
40 #include <list>
41 #include <vector>
42 #include <boost/function.hpp>
43 #include <boost/bind.hpp>
44 #include <boost/shared_ptr.hpp>
45 #include <boost/weak_ptr.hpp>
46 #include <boost/thread.hpp>
47 #include <boost/signals2.hpp>
48 
49 #include <ros/callback_queue.h>
50 
53 
54 #define TF_MESSAGEFILTER_DEBUG(fmt, ...) \
55  ROS_DEBUG_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
56 
57 #define TF_MESSAGEFILTER_WARN(fmt, ...) \
58  ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: " fmt, getTargetFramesString().c_str(), __VA_ARGS__)
59 
60 namespace tf
61 {
62 
63 namespace filter_failure_reasons
64 {
66 {
73 };
74 }
76 
78 {
79 public:
80  virtual ~MessageFilterBase(){}
81  virtual void clear() = 0;
82  virtual void setTargetFrame(const std::string& target_frame) = 0;
83  virtual void setTargetFrames(const std::vector<std::string>& target_frames) = 0;
84  virtual void setTolerance(const ros::Duration& tolerance) = 0;
85  virtual void setQueueSize( uint32_t new_queue_size ) = 0;
86  virtual uint32_t getQueueSize() = 0;
87 };
88 
105 template<class M>
107 {
108 public:
111  typedef boost::function<void(const MConstPtr&, FilterFailureReason)> FailureCallback;
112  typedef boost::signals2::signal<void(const MConstPtr&, FilterFailureReason)> FailureSignal;
113 
123  MessageFilter(Transformer& tf, const std::string& target_frame, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle(), ros::Duration max_rate = ros::Duration(0.01))
124  : tf_(tf)
125  , nh_(nh)
126  , max_rate_(max_rate)
127  , queue_size_(queue_size)
128  {
129  init();
130 
131  setTargetFrame(target_frame);
132  }
133 
144  template<class F>
145  MessageFilter(F& f, Transformer& tf, const std::string& target_frame, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle(), ros::Duration max_rate = ros::Duration(0.01))
146  : tf_(tf)
147  , nh_(nh)
148  , max_rate_(max_rate)
149  , queue_size_(queue_size)
150  {
151  init();
152 
153  setTargetFrame(target_frame);
154 
155  connectInput(f);
156  }
157 
161  template<class F>
162  void connectInput(F& f)
163  {
165  message_connection_ = f.registerCallback(&MessageFilter::incomingMessage, this);
166  }
167 
172  {
173  // Explicitly stop callbacks; they could execute after we're destroyed
177 
178  clear();
179 
180  TF_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Failed Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu",
181  (long long unsigned int)successful_transform_count_, (long long unsigned int)failed_transform_count_,
182  (long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_,
183  (long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_);
184 
185  }
186 
190  void setTargetFrame(const std::string& target_frame)
191  {
192  std::vector<std::string> frames;
193  frames.push_back(target_frame);
194  setTargetFrames(frames);
195  }
196 
200  void setTargetFrames(const std::vector<std::string>& target_frames)
201  {
202  boost::mutex::scoped_lock list_lock(messages_mutex_);
203  boost::mutex::scoped_lock string_lock(target_frames_string_mutex_);
204 
205  target_frames_ = target_frames;
206 
207  std::stringstream ss;
208  for (std::vector<std::string>::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it)
209  {
210  ss << *it << " ";
211  }
212  target_frames_string_ = ss.str();
213  }
217  std::string getTargetFramesString()
218  {
219  boost::mutex::scoped_lock lock(target_frames_string_mutex_);
220  return target_frames_string_;
221  };
222 
226  void setTolerance(const ros::Duration& tolerance)
227  {
228  time_tolerance_ = tolerance;
229  }
230 
234  void clear()
235  {
236  boost::mutex::scoped_lock lock(messages_mutex_);
237 
238  TF_MESSAGEFILTER_DEBUG("%s", "Cleared");
239 
240  messages_.clear();
241  message_count_ = 0;
242 
245  }
246 
247  void add(const MEvent& evt)
248  {
249  boost::mutex::scoped_lock lock(messages_mutex_);
250 
251  testMessages();
252 
253  if (!testMessage(evt))
254  {
255  // If this message is about to push us past our queue size, erase the oldest message
256  if (queue_size_ != 0 && message_count_ + 1 > queue_size_)
257  {
259  const MEvent& front = messages_.front();
261  "Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)",
266 
267  messages_.pop_front();
268  --message_count_;
269  }
270 
271  // Add the message to our list
272  messages_.push_back(evt);
273  ++message_count_;
274  }
275 
277  "Added message in frame %s at time %.3f, count now %d",
281 
283  }
284 
290  void add(const MConstPtr& message)
291  {
292 
293  boost::shared_ptr<std::map<std::string, std::string> > header(new std::map<std::string, std::string>);
294  (*header)["callerid"] = "unknown";
295  add(MEvent(message, header, ros::Time::now()));
296  }
297 
303  {
304  boost::mutex::scoped_lock lock(failure_signal_mutex_);
305  return message_filters::Connection(boost::bind(&MessageFilter::disconnectFailure, this, _1), failure_signal_.connect(callback));
306  }
307 
308  virtual void setQueueSize( uint32_t new_queue_size )
309  {
310  queue_size_ = new_queue_size;
311  }
312 
313  virtual uint32_t getQueueSize()
314  {
315  return queue_size_;
316  }
317 
318 private:
319 
320  void init()
321  {
322  message_count_ = 0;
323  new_transforms_ = false;
333 
335 
337  }
338 
339  typedef std::list<MEvent> L_Event;
340 
341  bool testMessage(const MEvent& evt)
342  {
343  const MConstPtr& message = evt.getMessage();
344  std::string callerid = evt.getPublisherName();
345  std::string frame_id = ros::message_traits::FrameId<M>::value(*message);
347 
348  //Throw out messages which have an empty frame_id
349  if (frame_id.empty())
350  {
352  {
354  TF_MESSAGEFILTER_WARN("Discarding message from [%s] due to empty frame_id. This message will only print once.", callerid.c_str());
355  }
357  return true;
358  }
359 
360 
361  //Throw out messages which are too old
363  for (std::vector<std::string>::iterator target_it = target_frames_.begin(); target_it != target_frames_.end(); ++target_it)
364  {
365  const std::string& target_frame = *target_it;
366 
367  if (target_frame != frame_id && stamp != ros::Time(0))
368  {
369  ros::Time latest_transform_time ;
370 
371  tf_.getLatestCommonTime(frame_id, target_frame, latest_transform_time, 0) ;
372 
373  if (stamp + tf_.getCacheLength() < latest_transform_time)
374  {
378  "Discarding Message, in frame %s, Out of the back of Cache Time "
379  "(stamp: %.3f + cache_length: %.3f < latest_transform_time %.3f. "
380  "Message Count now: %d",
381  ros::message_traits::FrameId<M>::value(*message).c_str(),
383  tf_.getCacheLength().toSec(), latest_transform_time.toSec(), message_count_);
384 
385  last_out_the_back_stamp_ = stamp;
386  last_out_the_back_frame_ = frame_id;
387 
389  return true;
390  }
391  }
392 
393  }
394 
395  bool ready = !target_frames_.empty();
396  for (std::vector<std::string>::iterator target_it = target_frames_.begin(); ready && target_it != target_frames_.end(); ++target_it)
397  {
398  std::string& target_frame = *target_it;
399  if (time_tolerance_ != ros::Duration(0.0))
400  {
401  ready = ready && (tf_.canTransform(target_frame, frame_id, stamp) &&
402  tf_.canTransform(target_frame, frame_id, stamp + time_tolerance_) );
403  }
404  else
405  {
406  ready = ready && tf_.canTransform(target_frame, frame_id, stamp);
407  }
408  }
409 
410  if (ready)
411  {
412  TF_MESSAGEFILTER_DEBUG("Message ready in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_);
413 
415 
416  this->signalMessage(evt);
417  }
418  else
419  {
421  }
422 
423  return ready;
424  }
425 
427  {
428  if (!messages_.empty() && getTargetFramesString() == " ")
429  {
430  ROS_WARN_NAMED("message_filter", "MessageFilter [target=%s]: empty target frame", getTargetFramesString().c_str());
431  }
432 
433  int i = 0;
434 
435  typename L_Event::iterator it = messages_.begin();
436  for (; it != messages_.end(); ++i)
437  {
438  MEvent& evt = *it;
439 
440  if (testMessage(evt))
441  {
442  --message_count_;
443  it = messages_.erase(it);
444  }
445  else
446  {
447  ++it;
448  }
449  }
450  }
451 
453  {
454  boost::mutex::scoped_lock list_lock(messages_mutex_);
455  if (new_transforms_)
456  {
457  testMessages();
458  new_transforms_ = false;
459  }
460 
461  checkFailures();
462  }
463 
468  {
469  add(evt);
470  }
471 
473  {
474  new_transforms_ = true;
475 
477  }
478 
480  {
482  {
484  }
485 
487  {
489  {
490  return;
491  }
492 
493  double dropped_pct = (double)dropped_message_count_ / (double)(incoming_message_count_ - message_count_);
494  if (dropped_pct > 0.95)
495  {
496  TF_MESSAGEFILTER_WARN("Dropped %.2f%% of messages so far. Please turn the [%s.message_filter] rosconsole logger to DEBUG for more information.", dropped_pct*100, ROSCONSOLE_DEFAULT_NAME);
498 
499  if ((double)failed_out_the_back_count_ / (double)dropped_message_count_ > 0.5)
500  {
501  TF_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());
502  }
503  }
504  }
505  }
506 
508  {
509  boost::mutex::scoped_lock lock(failure_signal_mutex_);
510  c.getBoostConnection().disconnect();
511  }
512 
513  void signalFailure(const MEvent& evt, FilterFailureReason reason)
514  {
515  boost::mutex::scoped_lock lock(failure_signal_mutex_);
516  failure_signal_(evt.getMessage(), reason);
517  }
518 
523  std::vector<std::string> target_frames_;
526  uint32_t queue_size_;
527 
529  uint32_t message_count_;
530  boost::mutex messages_mutex_;
531 
533  volatile bool new_transforms_;
534 
537 
544 
547 
549 
551 
552  boost::signals2::connection tf_connection_;
554 
556  boost::mutex failure_signal_mutex_;
557 };
558 
559 
560 } // namespace tf
561 
562 #endif
563 
tf::MessageFilter::new_transforms_
volatile bool new_transforms_
Used to skip waiting on new_data_ if new transforms have come in while calling back or transforming d...
Definition: message_filter.h:533
ros::message_traits::TimeStamp
tf::MessageFilter::messages_
L_Event messages_
The message list.
Definition: message_filter.h:528
tf::MessageFilter::failure_signal_mutex_
boost::mutex failure_signal_mutex_
Definition: message_filter.h:556
simple_filter.h
tf::MessageFilterBase::setTargetFrame
virtual void setTargetFrame(const std::string &target_frame)=0
message_filters::Connection::getBoostConnection
boost::signals2::connection getBoostConnection() const
tf::MessageFilterBase::~MessageFilterBase
virtual ~MessageFilterBase()
Definition: message_filter.h:80
tf::MessageFilter::getQueueSize
virtual uint32_t getQueueSize()
Definition: message_filter.h:313
tf::MessageFilter::warned_about_empty_frame_id_
bool warned_about_empty_frame_id_
Definition: message_filter.h:536
tf::Transformer::getCacheLength
ros::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition: tf.h:331
tf::MessageFilter::incoming_message_count_
uint64_t incoming_message_count_
Definition: message_filter.h:542
message_filters::Connection
TF_MESSAGEFILTER_DEBUG
#define TF_MESSAGEFILTER_DEBUG(fmt,...)
Definition: message_filter.h:54
tf::MessageFilter::messages_mutex_
boost::mutex messages_mutex_
The mutex used for locking message list operations.
Definition: message_filter.h:530
tf::MessageFilter::testMessages
void testMessages()
Definition: message_filter.h:426
boost::shared_ptr
tf::MessageFilter::tf_connection_
boost::signals2::connection tf_connection_
Definition: message_filter.h:552
tf::MessageFilter::target_frames_
std::vector< std::string > target_frames_
The frames we need to be able to transform to before a message is ready.
Definition: message_filter.h:523
tf::MessageFilter::setTolerance
void setTolerance(const ros::Duration &tolerance)
Set the required tolerance for the notifier to return true.
Definition: message_filter.h:226
tf::MessageFilter::failed_transform_count_
uint64_t failed_transform_count_
Definition: message_filter.h:539
ros.h
tf::MessageFilter::init
void init()
Definition: message_filter.h:320
TF_MESSAGEFILTER_WARN
#define TF_MESSAGEFILTER_WARN(fmt,...)
Definition: message_filter.h:57
ros::Timer::stop
void stop()
tf::MessageFilter::~MessageFilter
~MessageFilter()
Destructor.
Definition: message_filter.h:171
tf::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:162
ros::MessageEvent::getPublisherName
const std::string & getPublisherName() const
TimeBase< Time, Duration >::toSec
double toSec() const
tf::MessageFilter::queue_size_
uint32_t queue_size_
The maximum number of messages we queue up.
Definition: message_filter.h:526
tf::Transformer::canTransform
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
Test if a transform is possible.
Definition: tf.cpp:358
tf::Transformer::removeTransformsChangedListener
void removeTransformsChangedListener(boost::signals2::connection c)
Definition: tf.cpp:578
tf::Transformer
A Class which provides coordinate transforms between any two frames in a system.
Definition: tf.h:103
tf::MessageFilter::disconnectFailure
void disconnectFailure(const message_filters::Connection &c)
Definition: message_filter.h:507
tf::filter_failure_reasons::FilterFailureReason
FilterFailureReason
Definition: message_filter.h:65
tf::MessageFilter::MEvent
ros::MessageEvent< M const > MEvent
Definition: message_filter.h:110
tf::FilterFailureReason
filter_failure_reasons::FilterFailureReason FilterFailureReason
Definition: message_filter.h:75
f
f
tf::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:302
tf::MessageFilter::target_frames_string_mutex_
boost::mutex target_frames_string_mutex_
Definition: message_filter.h:525
message_filters::SimpleFilter
tf::MessageFilter::dropped_message_count_
uint64_t dropped_message_count_
Definition: message_filter.h:543
tf::MessageFilter::FailureSignal
boost::signals2::signal< void(const MConstPtr &, FilterFailureReason)> FailureSignal
Definition: message_filter.h:112
tf::MessageFilter::tf_
Transformer & tf_
The Transformer used to determine if transformation data is available.
Definition: message_filter.h:519
tf::MessageFilter::message_count_
uint32_t message_count_
The number of messages in the list. Used because messages_.size() has linear cost.
Definition: message_filter.h:529
tf::MessageFilter::last_out_the_back_stamp_
ros::Time last_out_the_back_stamp_
Definition: message_filter.h:545
tf::MessageFilter::getTargetFramesString
std::string getTargetFramesString()
Get the target frames as a string for debugging.
Definition: message_filter.h:217
tf::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:70
tf::MessageFilter::checkFailures
void checkFailures()
Definition: message_filter.h:479
tf::MessageFilter::setTargetFrames
void setTargetFrames(const std::vector< std::string > &target_frames)
Set the frames you need to be able to transform to before getting a message callback.
Definition: message_filter.h:200
tf::MessageFilter::failure_signal_
FailureSignal failure_signal_
Definition: message_filter.h:555
tf::MessageFilter::MessageFilter
MessageFilter(F &f, Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
Definition: message_filter.h:145
tf::MessageFilter::successful_transform_count_
uint64_t successful_transform_count_
Definition: message_filter.h:538
TimeBase< Time, Duration >::isZero
bool isZero() const
tf::MessageFilter::nh_
ros::NodeHandle nh_
The node used to subscribe to the topic.
Definition: message_filter.h:520
tf::MessageFilter::next_failure_warning_
ros::Time next_failure_warning_
Definition: message_filter.h:548
tf::MessageFilter::maxRateTimerCallback
void maxRateTimerCallback(const ros::TimerEvent &)
Definition: message_filter.h:452
tf::MessageFilter::add
void add(const MEvent &evt)
Definition: message_filter.h:247
tf::MessageFilter::FailureCallback
boost::function< void(const MConstPtr &, FilterFailureReason)> FailureCallback
Definition: message_filter.h:111
tf::MessageFilter::L_Event
std::list< MEvent > L_Event
Definition: message_filter.h:339
tf::MessageFilterBase::setTargetFrames
virtual void setTargetFrames(const std::vector< std::string > &target_frames)=0
tf::Transformer::getLatestCommonTime
int getLatestCommonTime(const std::string &source_frame, const std::string &target_frame, ros::Time &time, std::string *error_string) const
Return the latest rostime which is common across the spanning set zero if fails to cross.
Definition: tf.cpp:417
transform_listener.h
tf::MessageFilter::warned_about_unresolved_name_
bool warned_about_unresolved_name_
Definition: message_filter.h:535
tf::MessageFilterBase::clear
virtual void clear()=0
tf::MessageFilter::setQueueSize
virtual void setQueueSize(uint32_t new_queue_size)
Definition: message_filter.h:308
tf::filter_failure_reasons::EmptyFrameID
@ EmptyFrameID
The frame_id on the message is empty.
Definition: message_filter.h:72
tf::MessageFilter::max_rate_timer_
ros::Timer max_rate_timer_
Definition: message_filter.h:522
tf::MessageFilter::target_frames_string_
std::string target_frames_string_
Definition: message_filter.h:524
tf::MessageFilterBase
Definition: message_filter.h:77
ros::TimerEvent
tf::MessageFilter::add
void add(const MConstPtr &message)
Manually add a message into this filter.
Definition: message_filter.h:290
tf::MessageFilter::signalFailure
void signalFailure(const MEvent &evt, FilterFailureReason reason)
Definition: message_filter.h:513
callback_queue.h
tf::MessageFilter::new_messages_
bool new_messages_
Used to skip waiting on new_data_ if new messages have come in while calling back.
Definition: message_filter.h:532
tf::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:467
tf::MessageFilter::last_out_the_back_frame_
std::string last_out_the_back_frame_
Definition: message_filter.h:546
connection.h
tf::MessageFilter::max_rate_
ros::Duration max_rate_
Definition: message_filter.h:521
ros::Time
ros::message_traits::FrameId
tf::MessageFilter::MConstPtr
boost::shared_ptr< M const > MConstPtr
Definition: message_filter.h:109
tf::MessageFilter::transformsChanged
void transformsChanged()
Definition: message_filter.h:472
tf::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:190
tf::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:550
tf::MessageFilter
Follows the patterns set by the message_filters package to implement a filter which only passes messa...
Definition: message_filter.h:106
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
tf::MessageFilter::MessageFilter
MessageFilter(Transformer &tf, const std::string &target_frame, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle(), ros::Duration max_rate=ros::Duration(0.01))
Constructor.
Definition: message_filter.h:123
tf::Transformer::addTransformsChangedListener
boost::signals2::connection addTransformsChangedListener(boost::function< void(void)> callback)
Add a callback that happens when a new transform has arrived.
Definition: tf.cpp:573
tf::MessageFilter::clear
void clear()
Clear any messages currently in the queue.
Definition: message_filter.h:234
tf::MessageFilter::testMessage
bool testMessage(const MEvent &evt)
Definition: message_filter.h:341
tf::MessageFilterBase::setTolerance
virtual void setTolerance(const ros::Duration &tolerance)=0
tf
Definition: exceptions.h:38
ros::MessageEvent::getMessage
boost::shared_ptr< M > getMessage() const
DurationBase< Duration >::toSec
double toSec() const
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
tf::MessageFilterBase::getQueueSize
virtual uint32_t getQueueSize()=0
header
const std::string header
message_filters::SimpleFilter< M >::signalMessage
void signalMessage(const MConstPtr &msg)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
tf::MessageFilter::failed_out_the_back_count_
uint64_t failed_out_the_back_count_
Definition: message_filter.h:540
ros::Timer
tf::filter_failure_reasons::Unknown
@ Unknown
The message buffer overflowed, and this message was pushed off the back of the queue,...
Definition: message_filter.h:68
tf::MessageFilter::transform_message_count_
uint64_t transform_message_count_
Definition: message_filter.h:541
ros::NodeHandle
ros::MessageEvent
tf::MessageFilter::message_connection_
message_filters::Connection message_connection_
Definition: message_filter.h:553
ros::Time::now
static Time now()
tf::MessageFilterBase::setQueueSize
virtual void setQueueSize(uint32_t new_queue_size)=0
message_filters::Connection::disconnect
void disconnect()


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sat Aug 19 2023 02:38:07