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