30 #define BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC 38 #if BOOST_VERSION < 106100 39 #ifndef USING_BACKPORTED_BOOST_CONDITION_VARIABLE 40 #error "steady timer needs boost version >= 1.61 or the backported headers!" 56 boost::mutex::scoped_lock lock(timers_mutex_);
61 boost::mutex::scoped_lock waitlock(waiting_mutex_);
71 while (!waiting_.empty() && info && info->next_expected <= current)
76 CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(
this, info, info->last_expected, info->last_real, info->next_expected));
77 info->callback_queue->addCallback(cb, (uint64_t)info.get());
86 info = findTimer(waiting_.front());
91 sleep_end = info->next_expected;
100 if (current >= sleep_end)
107 boost::chrono::steady_clock::time_point end_tp(boost::chrono::nanoseconds(sleep_end.
toNSec()));
108 timers_cond_.wait_until(lock, end_tp);
122 ROS_DEBUG(
"SteadyTimer deregistering callbacks.");
212 return impl_->hasPending();
222 impl_->setPeriod(period, reset);
void start()
Start the timer. Does nothing if the timer is already started.
void remove(int32_t handle)
void stop()
Stop the timer. Once this call returns, no more callbacks will be called. Does nothing if the timer i...
VoidConstWPtr tracked_object_
SteadyTimerCallback callback
The callback to call.
WallDuration period
The period to call the callback at.
SteadyTimerCallback callback_
bool hasPending(int32_t handle)
void setPeriod(const WallDuration &period, bool reset=true)
Set the period of this timer.
int32_t add(const D &period, const boost::function< void(const E &)> &callback, CallbackQueueInterface *callback_queue, const VoidConstPtr &tracked_object, bool oneshot)
void setPeriod(const WallDuration &period, bool reset=true)
CallbackQueueInterface * callback_queue_
Manages a steady-clock timer callback.
bool hasPending()
Returns whether or not the timer has any pending events to call.
static TimerManager & global()
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Encapsulates all options available for starting a timer.
VoidConstPtr tracked_object
void setPeriod(int32_t handle, const D &period, bool reset=true)