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;
58 class TimerManagerTraits<SteadyTime>
61 typedef boost::chrono::steady_clock::time_point time_point;
65 template<
class T,
class D,
class E>
108 int32_t add(
const D& period,
const boost::function<
void(
const E&)>& callback,
CallbackQueueInterface* callback_queue,
const VoidConstPtr& tracked_object,
bool oneshot);
109 void remove(int32_t handle);
111 bool hasPending(int32_t handle);
112 void setPeriod(int32_t handle,
const D& period,
bool reset=
true);
123 bool waitingCompare(int32_t lhs, int32_t rhs);
124 TimerInfoPtr findTimer(int32_t handle);
125 void schedule(
const TimerInfoPtr& info);
126 void updateNext(
const TimerInfoPtr& info,
const T& current_time);
151 , last_expected_(last_expected)
152 , last_real_(last_real)
153 , current_expected_(current_expected)
156 boost::mutex::scoped_lock lock(info->waiting_mutex);
157 ++info->waiting_callbacks;
162 TimerInfoPtr info = info_.lock();
165 boost::mutex::scoped_lock lock(info->waiting_mutex);
166 --info->waiting_callbacks;
172 TimerInfoPtr info = info_.lock();
183 if (info->has_tracked_object)
185 tracked = info->tracked_object.lock();
193 event.last_expected = last_expected_;
194 event.last_real = last_real_;
195 event.current_expected = current_expected_;
196 event.current_real = T::now();
197 event.profile.last_duration = info->last_cb_duration;
200 info->callback(event);
202 info->last_cb_duration = cb_end - cb_start;
204 info->last_real =
event.current_real;
206 parent_->schedule(info);
223 template<
class T,
class D,
class E>
225 new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
228 template<
class T,
class D,
class E>
242 template<
class T,
class D,
class E>
247 if (!infol || !infor)
249 return infol < infor;
252 return infol->next_expected < infor->next_expected;
255 template<
class T,
class D,
class E>
258 typename V_TimerInfo::iterator it =
timers_.begin();
259 typename V_TimerInfo::iterator end =
timers_.end();
260 for (; it != end; ++it)
262 if ((*it)->handle == handle)
271 template<
class T,
class D,
class E>
282 if (info->has_tracked_object)
291 boost::mutex::scoped_lock lock2(info->waiting_mutex);
292 return info->next_expected <= T::now() || info->waiting_callbacks != 0;
295 template<
class T,
class D,
class E>
299 TimerInfoPtr info(boost::make_shared<TimerInfo>());
300 info->period = period;
301 info->callback = callback;
302 info->callback_queue = callback_queue;
303 info->last_expected = T::now();
304 info->next_expected = info->last_expected + period;
305 info->removed =
false;
306 info->has_tracked_object =
false;
307 info->waiting_callbacks = 0;
308 info->total_calls = 0;
309 info->oneshot = oneshot;
312 info->tracked_object = tracked_object;
313 info->has_tracked_object =
true;
317 boost::mutex::scoped_lock lock(
id_mutex_);
344 template<
class T,
class D,
class E>
348 uint64_t remove_id = 0;
353 typename V_TimerInfo::iterator it =
timers_.begin();
354 typename V_TimerInfo::iterator end =
timers_.end();
355 for (; it != end; ++it)
357 const TimerInfoPtr& info = *it;
358 if (info->handle == handle)
360 info->removed =
true;
361 callback_queue = info->callback_queue;
362 remove_id = (uint64_t)info.get();
385 template<
class T,
class D,
class E>
408 template<
class T,
class D,
class E>
413 info->next_expected = T(INT_MAX, 999999999);
420 if (info->next_expected <= current_time)
422 info->last_expected = info->next_expected;
423 info->next_expected += info->period;
427 if (info->next_expected + info->period < current_time)
429 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());
430 info->next_expected = current_time;
435 template<
class T,
class D,
class E>
451 info->next_expected = T::now() + period;
455 else if( (T::now() - info->last_real) < info->period)
459 if( (T::now() - info->last_real) > period)
461 info->next_expected = T::now();
467 info->next_expected = info->last_real + period;
474 info->period = period;
482 template<
class T,
class D,
class E>
493 if (T::now() < current)
499 typename V_TimerInfo::iterator it =
timers_.begin();
500 typename V_TimerInfo::iterator end =
timers_.end();
501 for (; it != end; ++it)
503 const TimerInfoPtr& info = *it;
506 if (current < info->last_expected)
508 info->last_expected = current;
509 info->next_expected = current + info->period;
521 sleep_end = current + D(0.1);
527 while (!
waiting_.empty() && info && info->next_expected <= current)
532 CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(
this, info, info->last_expected, info->last_real, info->next_expected));
533 info->callback_queue->addCallback(cb, (uint64_t)info.get());
547 sleep_end = info->next_expected;
556 if (T::now() < current)
564 if (current >= sleep_end)
571 if (!T::isSystemTime())
573 timers_cond_.wait_for(lock, boost::chrono::milliseconds(1));
579 typename TimerManagerTraits<T>::time_point end_tp(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
CallResult call()
Call this callback.
VoidConstWPtr tracked_object
TimerQueueCallback(TimerManager< T, D, E > *parent, const TimerInfoPtr &info, T last_expected, T last_real, T current_expected)
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)