28 #ifndef ROSCPP_TIMER_MANAGER_H
29 #define ROSCPP_TIMER_MANAGER_H
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>
51 class TimerManagerTraits
54 typedef boost::chrono::system_clock::time_point time_point;
55 typedef boost::chrono::system_clock::duration duration;
59 class TimerManagerTraits<SteadyTime>
62 typedef boost::chrono::steady_clock::time_point time_point;
63 typedef boost::chrono::steady_clock::duration duration;
67 template<
class T,
class D,
class E>
112 void remove(int32_t handle);
115 void setPeriod(int32_t handle,
const D& period,
bool reset=
true);
161 boost::mutex::scoped_lock lock(info->waiting_mutex);
162 ++info->waiting_callbacks;
170 boost::mutex::scoped_lock lock(info->waiting_mutex);
171 --info->waiting_callbacks;
188 if (info->has_tracked_object)
190 tracked = info->tracked_object.lock();
202 event.current_real = T::now();
204 event.profile.last_duration = info->last_cb_duration;
207 info->callback(event);
209 info->last_cb_duration = cb_end - cb_start;
211 info->last_real =
event.current_real;
212 info->last_expired =
event.current_expired;
233 template<
class T,
class D,
class E>
235 new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
237 #if !defined(BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC) && !defined(BOOST_THREAD_INTERNAL_CLOCK_IS_MONO)
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.");
246 template<
class T,
class D,
class E>
251 boost::mutex::scoped_lock lock(timers_mutex_);
252 timers_cond_.notify_all();
260 template<
class T,
class D,
class E>
265 if (!infol || !infor)
267 return infol < infor;
270 return infol->next_expected < infor->next_expected;
273 template<
class T,
class D,
class E>
276 typename V_TimerInfo::iterator it = timers_.begin();
277 typename V_TimerInfo::iterator end = timers_.end();
278 for (; it != end; ++it)
280 if ((*it)->handle == handle)
289 template<
class T,
class D,
class E>
292 boost::mutex::scoped_lock lock(timers_mutex_);
300 if (info->has_tracked_object)
309 boost::mutex::scoped_lock lock2(info->waiting_mutex);
310 return info->next_expected <= T::now() || info->waiting_callbacks != 0;
313 template<
class T,
class D,
class E>
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;
330 info->tracked_object = tracked_object;
331 info->has_tracked_object =
true;
335 boost::mutex::scoped_lock lock(id_mutex_);
336 info->handle = id_counter_++;
340 boost::mutex::scoped_lock lock(timers_mutex_);
341 timers_.push_back(info);
343 if (!thread_started_)
346 thread_started_ =
true;
350 boost::mutex::scoped_lock lock(waiting_mutex_);
351 waiting_.push_back(info->handle);
356 timers_cond_.notify_all();
362 template<
class T,
class D,
class E>
366 uint64_t remove_id = 0;
369 boost::mutex::scoped_lock lock(timers_mutex_);
371 typename V_TimerInfo::iterator it = timers_.begin();
372 typename V_TimerInfo::iterator end = timers_.end();
373 for (; it != end; ++it)
376 if (info->handle == handle)
378 info->removed =
true;
379 callback_queue = info->callback_queue;
380 remove_id = (uint64_t)info.get();
387 boost::mutex::scoped_lock lock2(waiting_mutex_);
389 L_int32::iterator it = std::find(waiting_.begin(), waiting_.end(), handle);
390 if (it != waiting_.end())
403 template<
class T,
class D,
class E>
406 boost::mutex::scoped_lock lock(timers_mutex_);
413 updateNext(info, T::now());
415 boost::mutex::scoped_lock lock(waiting_mutex_);
417 waiting_.push_back(info->handle);
423 timers_cond_.notify_one();
426 template<
class T,
class D,
class E>
431 info->next_expected = T(INT_MAX, 999999999);
438 if (info->next_expected <= current_time)
440 info->last_expected = info->next_expected;
441 info->next_expected += info->period;
445 if (info->next_expected + info->period < current_time)
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;
453 template<
class T,
class D,
class E>
456 boost::mutex::scoped_lock lock(timers_mutex_);
465 boost::mutex::scoped_lock lock(waiting_mutex_);
469 info->next_expected = T::now() + period;
473 else if( (T::now() - info->last_real) < info->period)
477 if( (T::now() - info->last_real) > period)
479 info->next_expected = T::now();
485 info->next_expected = info->last_real + period;
492 info->period = period;
497 timers_cond_.notify_one();
500 template<
class T,
class D,
class E>
508 boost::mutex::scoped_lock lock(timers_mutex_);
511 if (T::now() < current)
517 typename V_TimerInfo::iterator it = timers_.begin();
518 typename V_TimerInfo::iterator end = timers_.end();
519 for (; it != end; ++it)
524 if (current < info->last_expected)
526 info->last_expected = current;
527 info->next_expected = current + info->period;
535 boost::mutex::scoped_lock waitlock(waiting_mutex_);
537 if (waiting_.empty())
539 sleep_end = current + D(0.1);
545 while (!waiting_.empty() && info && info->next_expected <= current)
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());
553 waiting_.pop_front();
555 if (waiting_.empty())
560 info = findTimer(waiting_.front());
565 sleep_end = info->next_expected;
570 while (!new_timer_ && T::now() < sleep_end && !quit_)
574 if (T::now() < current)
582 if (current >= sleep_end)
589 if (!T::isSystemTime())
591 timers_cond_.wait_for(lock, boost::chrono::milliseconds(1));
597 typename TimerManagerTraits<T>::time_point end_tp(
598 boost::chrono::duration_cast<
typename TimerManagerTraits<T>::duration>(
599 boost::chrono::nanoseconds(sleep_end.toNSec())
602 timers_cond_.wait_until(lock, end_tp);