28 #ifndef ROSCPP_TIMER_MANAGER_H 29 #define ROSCPP_TIMER_MANAGER_H 35 #include <boost/thread/thread.hpp> 36 #include <boost/thread/mutex.hpp> 37 #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>
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);
114 bool hasPending(int32_t handle);
115 void setPeriod(int32_t handle,
const D& period,
bool reset=
true);
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);
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)
161 boost::mutex::scoped_lock lock(info->waiting_mutex);
162 ++info->waiting_callbacks;
167 TimerInfoPtr info = info_.lock();
170 boost::mutex::scoped_lock lock(info->waiting_mutex);
171 --info->waiting_callbacks;
177 TimerInfoPtr info = info_.lock();
188 if (info->has_tracked_object)
190 tracked = info->tracked_object.lock();
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;
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;
214 parent_->schedule(info);
233 template<
class T,
class D,
class E>
235 new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
238 template<
class T,
class D,
class E>
252 template<
class T,
class D,
class E>
257 if (!infol || !infor)
259 return infol < infor;
262 return infol->next_expected < infor->next_expected;
265 template<
class T,
class D,
class E>
268 typename V_TimerInfo::iterator it =
timers_.begin();
269 typename V_TimerInfo::iterator end =
timers_.end();
270 for (; it != end; ++it)
272 if ((*it)->handle == handle)
281 template<
class T,
class D,
class E>
292 if (info->has_tracked_object)
301 boost::mutex::scoped_lock lock2(info->waiting_mutex);
302 return info->next_expected <= T::now() || info->waiting_callbacks != 0;
305 template<
class T,
class D,
class E>
309 TimerInfoPtr info(boost::make_shared<TimerInfo>());
310 info->period = period;
311 info->callback = callback;
312 info->callback_queue = callback_queue;
313 info->last_expected = T::now();
314 info->next_expected = info->last_expected + period;
315 info->removed =
false;
316 info->has_tracked_object =
false;
317 info->waiting_callbacks = 0;
318 info->total_calls = 0;
319 info->oneshot = oneshot;
322 info->tracked_object = tracked_object;
323 info->has_tracked_object =
true;
327 boost::mutex::scoped_lock lock(
id_mutex_);
354 template<
class T,
class D,
class E>
358 uint64_t remove_id = 0;
363 typename V_TimerInfo::iterator it =
timers_.begin();
364 typename V_TimerInfo::iterator end =
timers_.end();
365 for (; it != end; ++it)
367 const TimerInfoPtr& info = *it;
368 if (info->handle == handle)
370 info->removed =
true;
371 callback_queue = info->callback_queue;
372 remove_id = (uint64_t)info.get();
395 template<
class T,
class D,
class E>
418 template<
class T,
class D,
class E>
423 info->next_expected = T(INT_MAX, 999999999);
430 if (info->next_expected <= current_time)
432 info->last_expected = info->next_expected;
433 info->next_expected += info->period;
437 if (info->next_expected + info->period < current_time)
439 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());
440 info->next_expected = current_time;
445 template<
class T,
class D,
class E>
461 info->next_expected = T::now() + period;
465 else if( (T::now() - info->last_real) < info->period)
469 if( (T::now() - info->last_real) > period)
471 info->next_expected = T::now();
477 info->next_expected = info->last_real + period;
484 info->period = period;
492 template<
class T,
class D,
class E>
503 if (T::now() < current)
509 typename V_TimerInfo::iterator it =
timers_.begin();
510 typename V_TimerInfo::iterator end =
timers_.end();
511 for (; it != end; ++it)
513 const TimerInfoPtr& info = *it;
516 if (current < info->last_expected)
518 info->last_expected = current;
519 info->next_expected = current + info->period;
531 sleep_end = current + D(0.1);
537 while (!
waiting_.empty() && info && info->next_expected <= current)
542 CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(
this, info, info->last_expected, info->last_real, info->next_expected, info->last_expired, current));
543 info->callback_queue->addCallback(cb, (uint64_t)info.get());
557 sleep_end = info->next_expected;
566 if (T::now() < current)
574 if (current >= sleep_end)
581 if (!T::isSystemTime())
583 timers_cond_.wait_for(lock, boost::chrono::milliseconds(1));
589 typename TimerManagerTraits<T>::time_point end_tp(
590 boost::chrono::duration_cast<
typename TimerManagerTraits<T>::duration>(
591 boost::chrono::nanoseconds(sleep_end.toNSec())
CallResult
Possible results for the call() method.
boost::function< void(const E &)> callback
void remove(int32_t handle)
std::list< int32_t > L_int32
Abstract interface for items which can be added to a CallbackQueueInterface.
Abstract interface for a queue used to handle all callbacks within roscpp.
TimerManager< T, D, E > * parent_
bool hasPending(int32_t handle)
virtual void removeByID(uint64_t owner_id)=0
Remove all callbacks associated with an owner id.
int32_t add(const D &period, const boost::function< void(const E &)> &callback, CallbackQueueInterface *callback_queue, const VoidConstPtr &tracked_object, bool oneshot)
boost::mutex waiting_mutex
#define ROSCPP_LOG_DEBUG(...)
boost::condition_variable condition_variable_monotonic
boost::weak_ptr< void const > VoidConstWPtr
WallDuration last_cb_duration
void threadFunc(boost::barrier *b)
void updateNext(const TimerInfoPtr &info, const T ¤t_time)
CallbackQueueInterface * callback_queue
TimerQueueCallback(TimerManager< T, D, E > *parent, const TimerInfoPtr &info, T last_expected, T last_real, T current_expected, T last_expired, T current_expired)
CallResult call()
Call this callback.
VoidConstWPtr tracked_object
uint32_t waiting_callbacks
bool waitingCompare(int32_t lhs, int32_t rhs)
boost::weak_ptr< TimerInfo > TimerInfoWPtr
boost::mutex timers_mutex_
boost::shared_ptr< TimerInfo > TimerInfoPtr
std::vector< TimerInfoPtr > V_TimerInfo
static TimerManager & global()
TimerInfoPtr findTimer(int32_t handle)
ros::internal::condition_variable_monotonic timers_cond_
boost::mutex waiting_mutex_
void schedule(const TimerInfoPtr &info)
void setPeriod(int32_t handle, const D &period, bool reset=true)