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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44