Skip to content

Commit 07eaf14

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
feat(clock): Allow to pass condition_variable for sleep
This allows us to wait on a external clock, while also have the ability to wake up, if an operation finishes. Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 0bf97e2 commit 07eaf14

File tree

2 files changed

+48
-3
lines changed

2 files changed

+48
-3
lines changed

rclcpp/include/rclcpp/clock.hpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,30 @@ class Clock
113113
Time until,
114114
Context::SharedPtr context = contexts::get_global_default_context());
115115

116+
/**
117+
* Sleep until a specified Time, according to clock type, with the ability to provide
118+
* a condition_variable to interrupt the sleep operation.
119+
*
120+
* For futher information see \rclcpp::Clock::sleep_until
121+
*
122+
* \param until absolute time according to current clock type to sleep until.
123+
* \param context the rclcpp context the clock should use to check that ROS is still initialized.
124+
* \param cv Conditional that is internally used for the sleep operation
125+
* \param ignore_wakeups if set to true, the function will ignore any wakeup until the given sleep time has passend
126+
* \return true immediately if `until` is in the past
127+
* \return true when the time `until` is reached
128+
* \return false if time cannot be reached reliably, for example from shutdown or a change
129+
* of time source.
130+
* \throws std::runtime_error if the context is invalid
131+
* \throws std::runtime_error if `until` has a different clock type from this clock
132+
*/
133+
bool
134+
sleep_until(
135+
Time until,
136+
std::condition_variable & cv,
137+
bool ignore_wakeups,
138+
Context::SharedPtr context = contexts::get_global_default_context());
139+
116140
/**
117141
* Sleep for a specified Duration.
118142
*

rclcpp/src/rclcpp/clock.cpp

Lines changed: 24 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,11 @@ Clock::now() const
8080
}
8181

8282
bool
83-
Clock::sleep_until(Time until, Context::SharedPtr context)
83+
Clock::sleep_until(
84+
Time until,
85+
std::condition_variable & cv,
86+
bool ignore_wakeups,
87+
Context::SharedPtr context)
8488
{
8589
if (!context || !context->is_valid()) {
8690
throw std::runtime_error("context cannot be slept with because it's invalid");
@@ -91,8 +95,6 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
9195
}
9296
bool time_source_changed = false;
9397

94-
std::condition_variable cv;
95-
9698
// Wake this thread if the context is shutdown
9799
rclcpp::OnShutdownCallbackHandle shutdown_cb_handle = context->add_on_shutdown_callback(
98100
[&cv]() {
@@ -116,6 +118,9 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
116118
std::unique_lock lock(impl_->clock_mutex_);
117119
while (now() < until && context->is_valid()) {
118120
cv.wait_until(lock, chrono_until);
121+
if (!ignore_wakeups) {
122+
break;
123+
}
119124
}
120125
} else if (this_clock_type == RCL_SYSTEM_TIME) {
121126
auto system_time = std::chrono::system_clock::time_point(
@@ -127,6 +132,9 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
127132
std::unique_lock lock(impl_->clock_mutex_);
128133
while (now() < until && context->is_valid()) {
129134
cv.wait_until(lock, system_time);
135+
if (!ignore_wakeups) {
136+
break;
137+
}
130138
}
131139
} else if (this_clock_type == RCL_ROS_TIME) {
132140
// Install jump handler for any amount of time change, for two purposes:
@@ -157,6 +165,9 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
157165
std::unique_lock lock(impl_->clock_mutex_);
158166
while (now() < until && context->is_valid() && !time_source_changed) {
159167
cv.wait_until(lock, system_time);
168+
if (!ignore_wakeups) {
169+
break;
170+
}
160171
}
161172
} else {
162173
// RCL_ROS_TIME with ros_time_is_active.
@@ -165,6 +176,9 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
165176
std::unique_lock lock(impl_->clock_mutex_);
166177
while (now() < until && context->is_valid() && !time_source_changed) {
167178
cv.wait(lock);
179+
if (!ignore_wakeups) {
180+
break;
181+
}
168182
}
169183
}
170184
}
@@ -176,6 +190,13 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
176190
return now() >= until;
177191
}
178192

193+
bool
194+
Clock::sleep_until(Time until, Context::SharedPtr context)
195+
{
196+
std::condition_variable cv;
197+
return sleep_until(until, cv, true, context);
198+
}
199+
179200
bool
180201
Clock::sleep_for(Duration rel_time, Context::SharedPtr context)
181202
{

0 commit comments

Comments
 (0)