timer_manager.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_TIMER_MANAGER_H
29 #define ROSCPP_TIMER_MANAGER_H
30 
31 #include "ros/forwards.h"
32 #include "ros/time.h"
33 #include "ros/file_log.h"
34 
35 #include <boost/thread/condition_variable.hpp>
36 #include <boost/thread/thread.hpp>
37 #include <boost/thread/mutex.hpp>
38 #include <boost/thread/recursive_mutex.hpp>
39 
40 #include "ros/assert.h"
42 
43 #include <boost/bind/bind.hpp>
44 
45 #include <vector>
46 #include <list>
47 
48 namespace ros
49 {
50 
51 namespace {
52  template<class T>
53  class TimerManagerTraits
54  {
55  public:
56  typedef boost::chrono::system_clock::time_point time_point;
57  typedef boost::chrono::system_clock::duration duration;
58  };
59 
60  template<>
61  class TimerManagerTraits<SteadyTime>
62  {
63  public:
64  typedef boost::chrono::steady_clock::time_point time_point;
65  typedef boost::chrono::steady_clock::duration duration;
66  };
67 }
68 
69 template<class T, class D, class E>
70 class TimerManager
71 {
72 private:
73  struct TimerInfo
74  {
75  int32_t handle;
76  D period;
77 
78  boost::function<void(const E&)> callback;
80 
82 
85 
88 
89  bool removed;
90 
93 
94  // TODO: atomicize
95  boost::mutex waiting_mutex;
97 
98  bool oneshot;
99 
100  // debugging info
101  uint32_t total_calls;
102  };
104  typedef boost::weak_ptr<TimerInfo> TimerInfoWPtr;
105  typedef std::vector<TimerInfoPtr> V_TimerInfo;
106 
107  typedef std::list<int32_t> L_int32;
108 
109 public:
110  TimerManager();
111  ~TimerManager();
112 
113  int32_t add(const D& period, const boost::function<void(const E&)>& callback, CallbackQueueInterface* callback_queue, const VoidConstPtr& tracked_object, bool oneshot);
114  void remove(int32_t handle);
115 
116  bool hasPending(int32_t handle);
117  void setPeriod(int32_t handle, const D& period, bool reset=true);
118 
120  {
122  return global;
123  }
124 
125 private:
126  void threadFunc();
127 
128  bool waitingCompare(int32_t lhs, int32_t rhs);
129  TimerInfoPtr findTimer(int32_t handle);
130  void schedule(const TimerInfoPtr& info);
131  void updateNext(const TimerInfoPtr& info, const T& current_time);
132 
134  boost::mutex timers_mutex_;
135  boost::condition_variable timers_cond_;
136  volatile bool new_timer_;
137 
138  boost::mutex waiting_mutex_;
140 
141  uint32_t id_counter_;
142  boost::mutex id_mutex_;
143 
145 
146  boost::thread thread_;
147 
148  bool quit_;
149 
151  {
152  public:
153  TimerQueueCallback(TimerManager<T, D, E>* parent, const TimerInfoPtr& info, T last_expected, T last_real, T current_expected, T last_expired, T current_expired)
154  : parent_(parent)
155  , info_(info)
156  , last_expected_(last_expected)
157  , last_real_(last_real)
158  , current_expected_(current_expected)
159  , last_expired_(last_expired)
160  , current_expired_(current_expired)
161  , called_(false)
162  {
163  boost::mutex::scoped_lock lock(info->waiting_mutex);
164  ++info->waiting_callbacks;
165  }
166 
168  {
169  TimerInfoPtr info = info_.lock();
170  if (info)
171  {
172  boost::mutex::scoped_lock lock(info->waiting_mutex);
173  --info->waiting_callbacks;
174  }
175  }
176 
178  {
179  TimerInfoPtr info = info_.lock();
180  if (!info)
181  {
182  return Invalid;
183  }
184 
185  {
186  ++info->total_calls;
187  called_ = true;
188 
189  VoidConstPtr tracked;
190  if (info->has_tracked_object)
191  {
192  tracked = info->tracked_object.lock();
193  if (!tracked)
194  {
195  return Invalid;
196  }
197  }
198 
199  E event;
200  event.last_expected = last_expected_;
201  event.last_real = last_real_;
202  event.last_expired = last_expired_;
203  event.current_expected = current_expected_;
204  event.current_real = T::now();
205  event.current_expired = current_expired_;
206  event.profile.last_duration = info->last_cb_duration;
207 
208  SteadyTime cb_start = SteadyTime::now();
209  info->callback(event);
210  SteadyTime cb_end = SteadyTime::now();
211  info->last_cb_duration = cb_end - cb_start;
212 
213  info->last_real = event.current_real;
214  info->last_expired = event.current_expired;
215 
216  parent_->schedule(info);
217  }
218 
219  return Success;
220  }
221 
222  private:
230 
231  bool called_;
232  };
233 };
234 
235 template<class T, class D, class E>
237  new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
238 {
239 #if !defined(BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC) && !defined(BOOST_THREAD_INTERNAL_CLOCK_IS_MONO)
240  ROS_ASSERT_MSG(false,
241  "ros::TimerManager was instantiated by package " ROS_PACKAGE_NAME ", but "
242  "neither BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC nor BOOST_THREAD_INTERNAL_CLOCK_IS_MONO is defined! "
243  "Be aware that timers might misbehave when system time jumps, "
244  "e.g. due to network time corrections.");
245 #endif
246 }
247 
248 template<class T, class D, class E>
250 {
251  quit_ = true;
252  {
253  boost::mutex::scoped_lock lock(timers_mutex_);
254  timers_cond_.notify_all();
255  }
256  if (thread_started_)
257  {
258  thread_.join();
259  }
260 }
261 
262 template<class T, class D, class E>
263 bool TimerManager<T, D, E>::waitingCompare(int32_t lhs, int32_t rhs)
264 {
265  TimerInfoPtr infol = findTimer(lhs);
266  TimerInfoPtr infor = findTimer(rhs);
267  if (!infol || !infor)
268  {
269  return infol < infor;
270  }
271 
272  return infol->next_expected < infor->next_expected;
273 }
274 
275 template<class T, class D, class E>
277 {
278  typename V_TimerInfo::iterator it = timers_.begin();
279  typename V_TimerInfo::iterator end = timers_.end();
280  for (; it != end; ++it)
281  {
282  if ((*it)->handle == handle)
283  {
284  return *it;
285  }
286  }
287 
288  return TimerInfoPtr();
289 }
290 
291 template<class T, class D, class E>
293 {
294  boost::mutex::scoped_lock lock(timers_mutex_);
295  TimerInfoPtr info = findTimer(handle);
296 
297  if (!info)
298  {
299  return false;
300  }
301 
302  if (info->has_tracked_object)
303  {
304  VoidConstPtr tracked = info->tracked_object.lock();
305  if (!tracked)
306  {
307  return false;
308  }
309  }
310 
311  boost::mutex::scoped_lock lock2(info->waiting_mutex);
312  return info->next_expected <= T::now() || info->waiting_callbacks != 0;
313 }
314 
315 template<class T, class D, class E>
316 int32_t TimerManager<T, D, E>::add(const D& period, const boost::function<void(const E&)>& callback, CallbackQueueInterface* callback_queue,
317  const VoidConstPtr& tracked_object, bool oneshot)
318 {
319  TimerInfoPtr info(boost::make_shared<TimerInfo>());
320  info->period = period;
321  info->callback = callback;
322  info->callback_queue = callback_queue;
323  info->last_expected = T::now();
324  info->next_expected = info->last_expected + period;
325  info->removed = false;
326  info->has_tracked_object = false;
327  info->waiting_callbacks = 0;
328  info->total_calls = 0;
329  info->oneshot = oneshot;
330  if (tracked_object)
331  {
332  info->tracked_object = tracked_object;
333  info->has_tracked_object = true;
334  }
335 
336  {
337  boost::mutex::scoped_lock lock(id_mutex_);
338  info->handle = id_counter_++;
339  }
340 
341  {
342  boost::mutex::scoped_lock lock(timers_mutex_);
343  timers_.push_back(info);
344 
345  if (!thread_started_)
346  {
347  thread_ = boost::thread(boost::bind(&TimerManager::threadFunc, this));
348  thread_started_ = true;
349  }
350 
351  {
352  boost::mutex::scoped_lock lock(waiting_mutex_);
353  waiting_.push_back(info->handle);
354  waiting_.sort(boost::bind(&TimerManager::waitingCompare, this, boost::placeholders::_1, boost::placeholders::_2));
355  }
356 
357  new_timer_ = true;
358  timers_cond_.notify_all();
359  }
360 
361  return info->handle;
362 }
363 
364 template<class T, class D, class E>
365 void TimerManager<T, D, E>::remove(int32_t handle)
366 {
367  CallbackQueueInterface* callback_queue = 0;
368  uint64_t remove_id = 0;
369 
370  {
371  boost::mutex::scoped_lock lock(timers_mutex_);
372 
373  typename V_TimerInfo::iterator it = timers_.begin();
374  typename V_TimerInfo::iterator end = timers_.end();
375  for (; it != end; ++it)
376  {
377  const TimerInfoPtr& info = *it;
378  if (info->handle == handle)
379  {
380  info->removed = true;
381  callback_queue = info->callback_queue;
382  remove_id = (uint64_t)info.get();
383  timers_.erase(it);
384  break;
385  }
386  }
387 
388  {
389  boost::mutex::scoped_lock lock2(waiting_mutex_);
390  // Remove from the waiting list if it's in it
391  L_int32::iterator it = std::find(waiting_.begin(), waiting_.end(), handle);
392  if (it != waiting_.end())
393  {
394  waiting_.erase(it);
395  }
396  }
397  }
398 
399  if (callback_queue)
400  {
401  callback_queue->removeByID(remove_id);
402  }
403 }
404 
405 template<class T, class D, class E>
407 {
408  boost::mutex::scoped_lock lock(timers_mutex_);
409 
410  if (info->removed)
411  {
412  return;
413  }
414 
415  updateNext(info, T::now());
416  {
417  boost::mutex::scoped_lock lock(waiting_mutex_);
418 
419  waiting_.push_back(info->handle);
420  // waitingCompare requires a lock on the timers_mutex_
421  waiting_.sort(boost::bind(&TimerManager::waitingCompare, this, boost::placeholders::_1, boost::placeholders::_2));
422  }
423 
424  new_timer_ = true;
425  timers_cond_.notify_one();
426 }
427 
428 template<class T, class D, class E>
429 void TimerManager<T, D, E>::updateNext(const TimerInfoPtr& info, const T& current_time)
430 {
431  if (info->oneshot)
432  {
433  info->next_expected = T(INT_MAX, 999999999);
434  }
435  else
436  {
437  // Protect against someone having called setPeriod()
438  // If the next expected time is already past the current time
439  // don't update it
440  if (info->next_expected <= current_time)
441  {
442  info->last_expected = info->next_expected;
443  info->next_expected += info->period;
444  }
445 
446  // detect time jumping forward, as well as callbacks that are too slow
447  if (info->next_expected + info->period < current_time)
448  {
449  ROS_DEBUG("Time jumped forward by [%f] for timer of period [%f], resetting timer (current=%f, next_expected=%f)", (current_time - info->next_expected).toSec(), info->period.toSec(), current_time.toSec(), info->next_expected.toSec());
450  info->next_expected = current_time;
451  }
452  }
453 }
454 
455 template<class T, class D, class E>
456 void TimerManager<T, D, E>::setPeriod(int32_t handle, const D& period, bool reset)
457 {
458  boost::mutex::scoped_lock lock(timers_mutex_);
459  TimerInfoPtr info = findTimer(handle);
460 
461  if (!info)
462  {
463  return;
464  }
465 
466  {
467  boost::mutex::scoped_lock lock(waiting_mutex_);
468 
469  if(reset)
470  {
471  info->next_expected = T::now() + period;
472  }
473 
474  // else if some time has elapsed since last cb (called outside of cb)
475  else if( (T::now() - info->last_real) < info->period)
476  {
477  // if elapsed time is greater than the new period
478  // do the callback now
479  if( (T::now() - info->last_real) > period)
480  {
481  info->next_expected = T::now();
482  }
483 
484  // else, account for elapsed time by using last_real+period
485  else
486  {
487  info->next_expected = info->last_real + period;
488  }
489  }
490 
491  // Else if called in a callback, last_real has not been updated yet => (now - last_real) > period
492  // In this case, let next_expected be updated only in updateNext
493 
494  info->period = period;
495  waiting_.sort(boost::bind(&TimerManager::waitingCompare, this, boost::placeholders::_1, boost::placeholders::_2));
496  }
497 
498  new_timer_ = true;
499  timers_cond_.notify_one();
500 }
501 
502 template<class T, class D, class E>
504 {
505  T current;
506  while (!quit_)
507  {
508  T sleep_end;
509 
510  boost::mutex::scoped_lock lock(timers_mutex_);
511 
512  // detect time jumping backwards
513  if (T::now() < current)
514  {
515  ROSCPP_LOG_DEBUG("Time jumped backward, resetting timers");
516 
517  current = T::now();
518 
519  typename V_TimerInfo::iterator it = timers_.begin();
520  typename V_TimerInfo::iterator end = timers_.end();
521  for (; it != end; ++it)
522  {
523  const TimerInfoPtr& info = *it;
524 
525  // Timer may have been added after the time jump, so also check if time has jumped past its last call time
526  if (current < info->last_expected)
527  {
528  info->last_expected = current;
529  info->next_expected = current + info->period;
530  }
531  }
532  }
533 
534  current = T::now();
535 
536  {
537  boost::mutex::scoped_lock waitlock(waiting_mutex_);
538 
539  if (waiting_.empty())
540  {
541  sleep_end = current + D(0.1);
542  }
543  else
544  {
545  TimerInfoPtr info = findTimer(waiting_.front());
546 
547  while (!waiting_.empty() && info && info->next_expected <= current)
548  {
549  current = T::now();
550 
551  //ROS_DEBUG("Scheduling timer callback for timer [%d] of period [%f], [%f] off expected", info->handle, info->period.toSec(), (current - info->next_expected).toSec());
552  CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(this, info, info->last_expected, info->last_real, info->next_expected, info->last_expired, current));
553  info->callback_queue->addCallback(cb, (uint64_t)info.get());
554 
555  waiting_.pop_front();
556 
557  if (waiting_.empty())
558  {
559  break;
560  }
561 
562  info = findTimer(waiting_.front());
563  }
564 
565  if (info)
566  {
567  sleep_end = info->next_expected;
568  }
569  }
570  }
571 
572  while (!new_timer_ && T::now() < sleep_end && !quit_)
573  {
574  // detect backwards jumps in time
575 
576  if (T::now() < current)
577  {
578  ROSCPP_LOG_DEBUG("Time jumped backwards, breaking out of sleep");
579  break;
580  }
581 
582  current = T::now();
583 
584  if (current >= sleep_end)
585  {
586  break;
587  }
588 
589  // If we're on simulation time we need to check now() against sleep_end more often than on system time,
590  // since simulation time may be running faster than real time.
591  if (!T::isSystemTime())
592  {
593  timers_cond_.wait_for(lock, boost::chrono::milliseconds(1));
594  }
595  else
596  {
597  // On system time we can simply sleep for the rest of the wait time, since anything else requiring processing will
598  // signal the condition variable
599  typename TimerManagerTraits<T>::time_point end_tp(
600  boost::chrono::duration_cast<typename TimerManagerTraits<T>::duration>(
601  boost::chrono::nanoseconds(sleep_end.toNSec())
602  )
603  );
604  timers_cond_.wait_until(lock, end_tp);
605  }
606  }
607 
608  new_timer_ = false;
609  }
610 }
611 
612 }
613 
614 #endif
ros::CallbackInterface::Invalid
@ Invalid
Call no longer valid.
Definition: callback_queue_interface.h:58
ros::TimerManager::thread_started_
bool thread_started_
Definition: timer_manager.h:144
ros::TimerManager::TimerQueueCallback::current_expired_
T current_expired_
Definition: timer_manager.h:229
callback_queue_interface.h
ros::TimerManager::TimerInfo::waiting_callbacks
uint32_t waiting_callbacks
Definition: timer_manager.h:96
ros::TimerManager::TimerInfoPtr
boost::shared_ptr< TimerInfo > TimerInfoPtr
Definition: timer_manager.h:103
ros::TimerManager::TimerQueueCallback::current_expected_
T current_expected_
Definition: timer_manager.h:227
ros::TimerManager::id_counter_
uint32_t id_counter_
Definition: timer_manager.h:141
boost::shared_ptr
ros::TimerManager::quit_
bool quit_
Definition: timer_manager.h:148
forwards.h
ros::TimerManager::updateNext
void updateNext(const TimerInfoPtr &info, const T &current_time)
Definition: timer_manager.h:429
ros::TimerManager::schedule
void schedule(const TimerInfoPtr &info)
Definition: timer_manager.h:406
ros::TimerManager::TimerInfo::oneshot
bool oneshot
Definition: timer_manager.h:98
ros
ros::TimerManager::TimerInfo::handle
int32_t handle
Definition: timer_manager.h:75
ros::TimerManager::TimerInfo::last_expected
T last_expected
Definition: timer_manager.h:83
time.h
ros::TimerManager::TimerQueueCallback::parent_
TimerManager< T, D, E > * parent_
Definition: timer_manager.h:223
ros::TimerManager::id_mutex_
boost::mutex id_mutex_
Definition: timer_manager.h:142
ros::TimerManager::~TimerManager
~TimerManager()
Definition: timer_manager.h:249
ros::TimerManager::TimerInfo::tracked_object
VoidConstWPtr tracked_object
Definition: timer_manager.h:91
ros::TimerManager::waiting_
L_int32 waiting_
Definition: timer_manager.h:139
ros::TimerManager::TimerQueueCallback::last_expected_
T last_expected_
Definition: timer_manager.h:225
ros::TimerManager::thread_
boost::thread thread_
Definition: timer_manager.h:146
ros::TimerManager::new_timer_
volatile bool new_timer_
Definition: timer_manager.h:136
ros::CallbackInterface::CallResult
CallResult
Possible results for the call() method.
Definition: callback_queue_interface.h:54
ros::TimerManager
Definition: internal_timer_manager.h:38
ros::TimerManager::TimerInfo::period
D period
Definition: timer_manager.h:76
ros::TimerManager::V_TimerInfo
std::vector< TimerInfoPtr > V_TimerInfo
Definition: timer_manager.h:105
ros::TimerManager::TimerQueueCallback::~TimerQueueCallback
~TimerQueueCallback()
Definition: timer_manager.h:167
ros::TimerManager::add
int32_t add(const D &period, const boost::function< void(const E &)> &callback, CallbackQueueInterface *callback_queue, const VoidConstPtr &tracked_object, bool oneshot)
Definition: timer_manager.h:316
ros::SteadyTime::now
static SteadyTime now()
ros::TimerManager::findTimer
TimerInfoPtr findTimer(int32_t handle)
Definition: timer_manager.h:276
ros::TimerManager::TimerInfo::next_expected
T next_expected
Definition: timer_manager.h:84
ROS_DEBUG
#define ROS_DEBUG(...)
ros::SteadyTime
ros::TimerManager::threadFunc
void threadFunc()
Definition: timer_manager.h:503
ros::TimerManager::TimerInfo::waiting_mutex
boost::mutex waiting_mutex
Definition: timer_manager.h:95
ros::TimerManager::TimerInfo::last_expired
T last_expired
Definition: timer_manager.h:87
ros::CallbackQueueInterface::removeByID
virtual void removeByID(uint64_t owner_id)=0
Remove all callbacks associated with an owner id.
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
ros::TimerManager::TimerManager
TimerManager()
Definition: timer_manager.h:236
ros::TimerManager::waitingCompare
bool waitingCompare(int32_t lhs, int32_t rhs)
Definition: timer_manager.h:263
ros::CallbackInterface
Abstract interface for items which can be added to a CallbackQueueInterface.
Definition: callback_queue_interface.h:48
ros::TimerManager::TimerQueueCallback::call
CallResult call()
Call this callback.
Definition: timer_manager.h:177
ros::TimerManager::TimerQueueCallback::last_real_
T last_real_
Definition: timer_manager.h:226
ros::TimerManager::TimerInfo
Definition: timer_manager.h:73
ros::CallbackInterface::Success
@ Success
Call succeeded.
Definition: callback_queue_interface.h:56
ros::TimerManager::TimerQueueCallback::TimerQueueCallback
TimerQueueCallback(TimerManager< T, D, E > *parent, const TimerInfoPtr &info, T last_expected, T last_real, T current_expected, T last_expired, T current_expired)
Definition: timer_manager.h:153
ros::TimerManager::setPeriod
void setPeriod(int32_t handle, const D &period, bool reset=true)
Definition: timer_manager.h:456
ros::TimerManager::L_int32
std::list< int32_t > L_int32
Definition: timer_manager.h:107
ros::TimerManager::TimerInfo::total_calls
uint32_t total_calls
Definition: timer_manager.h:101
ros::TimerManager::waiting_mutex_
boost::mutex waiting_mutex_
Definition: timer_manager.h:138
ros::VoidConstWPtr
boost::weak_ptr< void const > VoidConstWPtr
Definition: forwards.h:53
ros::TimerManager::TimerInfo::last_real
T last_real
Definition: timer_manager.h:86
ros::TimerManager::TimerInfoWPtr
boost::weak_ptr< TimerInfo > TimerInfoWPtr
Definition: timer_manager.h:104
ros::TimerManager::timers_mutex_
boost::mutex timers_mutex_
Definition: timer_manager.h:134
ros::TimerManager::TimerInfo::callback_queue
CallbackQueueInterface * callback_queue
Definition: timer_manager.h:79
ros::TimerManager::TimerInfo::removed
bool removed
Definition: timer_manager.h:89
ros::TimerManager::remove
void remove(int32_t handle)
Definition: timer_manager.h:365
ros::TimerManager::timers_cond_
boost::condition_variable timers_cond_
Definition: timer_manager.h:135
ros::TimerManager::TimerInfo::last_cb_duration
WallDuration last_cb_duration
Definition: timer_manager.h:81
ros::TimerManager::TimerQueueCallback::called_
bool called_
Definition: timer_manager.h:231
ros::TimerManager::TimerInfo::has_tracked_object
bool has_tracked_object
Definition: timer_manager.h:92
ros::TimerManager::TimerQueueCallback::last_expired_
T last_expired_
Definition: timer_manager.h:228
ros::WallDuration
assert.h
ros::TimerManager::timers_
V_TimerInfo timers_
Definition: timer_manager.h:133
ros::TimerManager::TimerQueueCallback
Definition: timer_manager.h:150
ros::TimerManager::hasPending
bool hasPending(int32_t handle)
Definition: timer_manager.h:292
ROSCPP_LOG_DEBUG
#define ROSCPP_LOG_DEBUG(...)
Definition: file_log.h:35
ros::CallbackQueueInterface
Abstract interface for a queue used to handle all callbacks within roscpp.
Definition: callback_queue_interface.h:82
ros::TimerManager::TimerInfo::callback
boost::function< void(const E &)> callback
Definition: timer_manager.h:78
ros::TimerManager::TimerQueueCallback::info_
TimerInfoWPtr info_
Definition: timer_manager.h:224
file_log.h
ros::TimerManager::global
static TimerManager & global()
Definition: timer_manager.h:119


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Tue May 20 2025 03:00:11