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>
43 #include <boost/bind/bind.hpp>
53 class TimerManagerTraits
56 typedef boost::chrono::system_clock::time_point time_point;
57 typedef boost::chrono::system_clock::duration duration;
61 class TimerManagerTraits<SteadyTime>
64 typedef boost::chrono::steady_clock::time_point time_point;
65 typedef boost::chrono::steady_clock::duration duration;
69 template<
class T,
class D,
class E>
114 void remove(int32_t handle);
117 void setPeriod(int32_t handle,
const D& period,
bool reset=
true);
163 boost::mutex::scoped_lock lock(info->waiting_mutex);
164 ++info->waiting_callbacks;
172 boost::mutex::scoped_lock lock(info->waiting_mutex);
173 --info->waiting_callbacks;
190 if (info->has_tracked_object)
192 tracked = info->tracked_object.lock();
204 event.current_real = T::now();
206 event.profile.last_duration = info->last_cb_duration;
209 info->callback(event);
211 info->last_cb_duration = cb_end - cb_start;
213 info->last_real =
event.current_real;
214 info->last_expired =
event.current_expired;
235 template<
class T,
class D,
class E>
237 new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
239 #if !defined(BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC) && !defined(BOOST_THREAD_INTERNAL_CLOCK_IS_MONO)
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.");
248 template<
class T,
class D,
class E>
253 boost::mutex::scoped_lock lock(timers_mutex_);
254 timers_cond_.notify_all();
262 template<
class T,
class D,
class E>
267 if (!infol || !infor)
269 return infol < infor;
272 return infol->next_expected < infor->next_expected;
275 template<
class T,
class D,
class E>
278 typename V_TimerInfo::iterator it = timers_.begin();
279 typename V_TimerInfo::iterator end = timers_.end();
280 for (; it != end; ++it)
282 if ((*it)->handle == handle)
291 template<
class T,
class D,
class E>
294 boost::mutex::scoped_lock lock(timers_mutex_);
302 if (info->has_tracked_object)
311 boost::mutex::scoped_lock lock2(info->waiting_mutex);
312 return info->next_expected <= T::now() || info->waiting_callbacks != 0;
315 template<
class T,
class D,
class E>
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;
332 info->tracked_object = tracked_object;
333 info->has_tracked_object =
true;
337 boost::mutex::scoped_lock lock(id_mutex_);
338 info->handle = id_counter_++;
342 boost::mutex::scoped_lock lock(timers_mutex_);
343 timers_.push_back(info);
345 if (!thread_started_)
348 thread_started_ =
true;
352 boost::mutex::scoped_lock lock(waiting_mutex_);
353 waiting_.push_back(info->handle);
358 timers_cond_.notify_all();
364 template<
class T,
class D,
class E>
368 uint64_t remove_id = 0;
371 boost::mutex::scoped_lock lock(timers_mutex_);
373 typename V_TimerInfo::iterator it = timers_.begin();
374 typename V_TimerInfo::iterator end = timers_.end();
375 for (; it != end; ++it)
378 if (info->handle == handle)
380 info->removed =
true;
381 callback_queue = info->callback_queue;
382 remove_id = (uint64_t)info.get();
389 boost::mutex::scoped_lock lock2(waiting_mutex_);
391 L_int32::iterator it = std::find(waiting_.begin(), waiting_.end(), handle);
392 if (it != waiting_.end())
405 template<
class T,
class D,
class E>
408 boost::mutex::scoped_lock lock(timers_mutex_);
415 updateNext(info, T::now());
417 boost::mutex::scoped_lock lock(waiting_mutex_);
419 waiting_.push_back(info->handle);
425 timers_cond_.notify_one();
428 template<
class T,
class D,
class E>
433 info->next_expected = T(INT_MAX, 999999999);
440 if (info->next_expected <= current_time)
442 info->last_expected = info->next_expected;
443 info->next_expected += info->period;
447 if (info->next_expected + info->period < current_time)
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;
455 template<
class T,
class D,
class E>
458 boost::mutex::scoped_lock lock(timers_mutex_);
467 boost::mutex::scoped_lock lock(waiting_mutex_);
471 info->next_expected = T::now() + period;
475 else if( (T::now() - info->last_real) < info->period)
479 if( (T::now() - info->last_real) > period)
481 info->next_expected = T::now();
487 info->next_expected = info->last_real + period;
494 info->period = period;
499 timers_cond_.notify_one();
502 template<
class T,
class D,
class E>
510 boost::mutex::scoped_lock lock(timers_mutex_);
513 if (T::now() < current)
519 typename V_TimerInfo::iterator it = timers_.begin();
520 typename V_TimerInfo::iterator end = timers_.end();
521 for (; it != end; ++it)
526 if (current < info->last_expected)
528 info->last_expected = current;
529 info->next_expected = current + info->period;
537 boost::mutex::scoped_lock waitlock(waiting_mutex_);
539 if (waiting_.empty())
541 sleep_end = current + D(0.1);
547 while (!waiting_.empty() && info && info->next_expected <= current)
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());
555 waiting_.pop_front();
557 if (waiting_.empty())
562 info = findTimer(waiting_.front());
567 sleep_end = info->next_expected;
572 while (!new_timer_ && T::now() < sleep_end && !quit_)
576 if (T::now() < current)
584 if (current >= sleep_end)
591 if (!T::isSystemTime())
593 timers_cond_.wait_for(lock, boost::chrono::milliseconds(1));
599 typename TimerManagerTraits<T>::time_point end_tp(
600 boost::chrono::duration_cast<
typename TimerManagerTraits<T>::duration>(
601 boost::chrono::nanoseconds(sleep_end.toNSec())
604 timers_cond_.wait_until(lock, end_tp);