steady_timer.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017, Felix Ruess, Roboception GmbH
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 // Make sure we use CLOCK_MONOTONIC for the condition variable if not Apple.
29 #ifndef __APPLE__
30 #define BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
31 #endif
32 
33 #include "ros/steady_timer.h"
34 #include "ros/timer_manager.h"
35 
36 // check if we have really included the backported boost condition variable
37 // just in case someone messes with the include order...
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!"
41 #endif
42 #endif
43 
44 namespace ros
45 {
46 
47 // specialization for SteadyTimer, to make sure we use a version with wait_until that uses the monotonic clock
48 template<>
50 {
51  SteadyTime current;
52  while (!quit_)
53  {
54  SteadyTime sleep_end;
55 
56  boost::mutex::scoped_lock lock(timers_mutex_);
57 
58  current = SteadyTime::now();
59 
60  {
61  boost::mutex::scoped_lock waitlock(waiting_mutex_);
62 
63  if (waiting_.empty())
64  {
65  sleep_end = current + WallDuration(0.1);
66  }
67  else
68  {
69  TimerInfoPtr info = findTimer(waiting_.front());
70 
71  while (!waiting_.empty() && info && info->next_expected <= current)
72  {
73  current = SteadyTime::now();
74 
75  //ROS_DEBUG("Scheduling timer callback for timer [%d] of period [%f], [%f] off expected", info->handle, info->period.toSec(), (current - info->next_expected).toSec());
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());
78 
79  waiting_.pop_front();
80 
81  if (waiting_.empty())
82  {
83  break;
84  }
85 
86  info = findTimer(waiting_.front());
87  }
88 
89  if (info)
90  {
91  sleep_end = info->next_expected;
92  }
93  }
94  }
95 
96  while (!new_timer_ && SteadyTime::now() < sleep_end && !quit_)
97  {
98  current = SteadyTime::now();
99 
100  if (current >= sleep_end)
101  {
102  break;
103  }
104 
105  // requires boost 1.61 for wait_until to actually use the steady clock
106  // see: https://svn.boost.org/trac/boost/ticket/6377
107  boost::chrono::steady_clock::time_point end_tp(boost::chrono::nanoseconds(sleep_end.toNSec()));
108  timers_cond_.wait_until(lock, end_tp);
109  }
110 
111  new_timer_ = false;
112  }
113 }
114 
116  : started_(false)
117  , timer_handle_(-1)
118 { }
119 
121 {
122  ROS_DEBUG("SteadyTimer deregistering callbacks.");
123  stop();
124 }
125 
127 {
128  if (!started_)
129  {
130  VoidConstPtr tracked_object;
132  {
133  tracked_object = tracked_object_.lock();
134  }
136  started_ = true;
137  }
138 }
139 
141 {
142  if (started_)
143  {
144  started_ = false;
146  timer_handle_ = -1;
147  }
148 }
149 
151 {
152  return !period_.isZero();
153 }
154 
156 {
157  if (!isValid() || timer_handle_ == -1)
158  {
159  return false;
160  }
161 
163 }
164 
165 void SteadyTimer::Impl::setPeriod(const WallDuration& period, bool reset)
166 {
167  period_ = period;
169 }
170 
171 
173 : impl_(new Impl)
174 {
175  impl_->period_ = ops.period;
176  impl_->callback_ = ops.callback;
177  impl_->callback_queue_ = ops.callback_queue;
178  impl_->tracked_object_ = ops.tracked_object;
179  impl_->has_tracked_object_ = (ops.tracked_object != NULL);
180  impl_->oneshot_ = ops.oneshot;
181 }
182 
184 {
185  impl_ = rhs.impl_;
186 }
187 
189 {
190 }
191 
193 {
194  if (impl_)
195  {
196  impl_->start();
197  }
198 }
199 
201 {
202  if (impl_)
203  {
204  impl_->stop();
205  }
206 }
207 
209 {
210  if (impl_)
211  {
212  return impl_->hasPending();
213  }
214 
215  return false;
216 }
217 
218 void SteadyTimer::setPeriod(const WallDuration& period, bool reset)
219 {
220  if (impl_)
221  {
222  impl_->setPeriod(period, reset);
223  }
224 }
225 
226 }
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_
Definition: steady_timer.h:113
SteadyTimerCallback callback
The callback to call.
WallDuration period
The period to call the callback at.
SteadyTimerCallback callback_
Definition: steady_timer.h:111
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)
static SteadyTime now()
CallbackQueueInterface * callback_queue_
Definition: steady_timer.h:112
Manages a steady-clock timer callback.
Definition: steady_timer.h:46
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.
#define ROS_DEBUG(...)
void setPeriod(int32_t handle, const D &period, bool reset=true)


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54