Skip to content

Commit 6bb9407

Browse files
wjwwoodJanosch Machowinskijmachowinski
authored
Reduce overhead for inheriting from rclcpp::Executor when base functionality is not reused (#2506)
* feat(clock): Added function to interrupt sleep This is useful in case a second thread needs to wake up another thread, that is sleeping using a clock. Signed-off-by: Janosch Machowinski <[email protected]> * feat: Added support for multi thread wait / shutdown This adds support for multiple threads waiting on the same clock, while an shutdown is invoked. Signed-off-by: Janosch Machowinski <[email protected]> * chore: Made Executor fully overloadable This commit makes every public funciton virtual, and adds virtual impl function for the existing template functions. The goal of this commit is to be able to fully control the everything from a derived class. Signed-off-by: Janosch Machowinski <[email protected]> * Update rclcpp/include/rclcpp/executor.hpp Co-authored-by: William Woodall <[email protected]> Signed-off-by: jmachowinski <[email protected]> * Update rclcpp/include/rclcpp/executor.hpp Co-authored-by: William Woodall <[email protected]> Signed-off-by: jmachowinski <[email protected]> * Update rclcpp/include/rclcpp/executor.hpp Co-authored-by: William Woodall <[email protected]> Signed-off-by: jmachowinski <[email protected]> * Update rclcpp/include/rclcpp/executor.hpp Co-authored-by: William Woodall <[email protected]> Signed-off-by: jmachowinski <[email protected]> * docs: added doc string for spin_until_future_complete_impl Signed-off-by: Janosch Machowinski <[email protected]> * made is_spinning not virtual Signed-off-by: Janosch Machowinski <[email protected]> * feat: Changed interface of spin_until_future_complete_impl This change allows it to use a second thread to wait for the future to become ready. Signed-off-by: Janosch Machowinski <[email protected]> * doc fixup Signed-off-by: William Woodall <[email protected]> * undo template->implicit conversion change Signed-off-by: William Woodall <[email protected]> * style Signed-off-by: William Woodall <[email protected]> --------- Signed-off-by: Janosch Machowinski <[email protected]> Signed-off-by: Janosch Machowinski <[email protected]> Signed-off-by: jmachowinski <[email protected]> Signed-off-by: William Woodall <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]> Co-authored-by: jmachowinski <[email protected]>
1 parent 535d56f commit 6bb9407

File tree

6 files changed

+390
-73
lines changed

6 files changed

+390
-73
lines changed

rclcpp/include/rclcpp/clock.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -193,6 +193,16 @@ class Clock
193193
bool
194194
ros_time_is_active();
195195

196+
/**
197+
* Cancels an ongoing or future sleep operation of one thread.
198+
*
199+
* This function can be used by one thread, to wakeup another thread that is
200+
* blocked using any of the sleep_ or wait_ methods of this class.
201+
*/
202+
RCLCPP_PUBLIC
203+
void
204+
cancel_sleep_or_wait();
205+
196206
/// Return the rcl_clock_t clock handle
197207
RCLCPP_PUBLIC
198208
rcl_clock_t *

rclcpp/include/rclcpp/executor.hpp

Lines changed: 35 additions & 50 deletions
Original file line numberDiff line numberDiff line change
@@ -272,12 +272,12 @@ class Executor
272272
* \param[in] node Shared pointer to the node to add.
273273
*/
274274
RCLCPP_PUBLIC
275-
void
275+
virtual void
276276
spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node);
277277

278278
/// Convenience function which takes Node and forwards NodeBaseInterface.
279279
RCLCPP_PUBLIC
280-
void
280+
virtual void
281281
spin_node_some(std::shared_ptr<rclcpp::Node> node);
282282

283283
/// Collect work once and execute all available work, optionally within a max duration.
@@ -307,14 +307,14 @@ class Executor
307307
* \param[in] node Shared pointer to the node to add.
308308
*/
309309
RCLCPP_PUBLIC
310-
void
310+
virtual void
311311
spin_node_all(
312312
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
313313
std::chrono::nanoseconds max_duration);
314314

315315
/// Convenience function which takes Node and forwards NodeBaseInterface.
316316
RCLCPP_PUBLIC
317-
void
317+
virtual void
318318
spin_node_all(std::shared_ptr<rclcpp::Node> node, std::chrono::nanoseconds max_duration);
319319

320320
/// Collect and execute work repeatedly within a duration or until no more work is available.
@@ -366,52 +366,12 @@ class Executor
366366
const FutureT & future,
367367
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
368368
{
369-
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
370-
// inside a callback executed by an executor.
371-
372-
// Check the future before entering the while loop.
373-
// If the future is already complete, don't try to spin.
374-
std::future_status status = future.wait_for(std::chrono::seconds(0));
375-
if (status == std::future_status::ready) {
376-
return FutureReturnCode::SUCCESS;
377-
}
378-
379-
auto end_time = std::chrono::steady_clock::now();
380-
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
381-
timeout);
382-
if (timeout_ns > std::chrono::nanoseconds::zero()) {
383-
end_time += timeout_ns;
384-
}
385-
std::chrono::nanoseconds timeout_left = timeout_ns;
386-
387-
if (spinning.exchange(true)) {
388-
throw std::runtime_error("spin_until_future_complete() called while already spinning");
389-
}
390-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
391-
while (rclcpp::ok(this->context_) && spinning.load()) {
392-
// Do one item of work.
393-
spin_once_impl(timeout_left);
394-
395-
// Check if the future is set, return SUCCESS if it is.
396-
status = future.wait_for(std::chrono::seconds(0));
397-
if (status == std::future_status::ready) {
398-
return FutureReturnCode::SUCCESS;
399-
}
400-
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
401-
if (timeout_ns < std::chrono::nanoseconds::zero()) {
402-
continue;
369+
return spin_until_future_complete_impl(
370+
std::chrono::duration_cast<std::chrono::nanoseconds>(timeout),
371+
[&future](std::chrono::nanoseconds wait_time) {
372+
return future.wait_for(wait_time);
403373
}
404-
// Otherwise check if we still have time to wait, return TIMEOUT if not.
405-
auto now = std::chrono::steady_clock::now();
406-
if (now >= end_time) {
407-
return FutureReturnCode::TIMEOUT;
408-
}
409-
// Subtract the elapsed time from the original timeout.
410-
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
411-
}
412-
413-
// The future did not complete before ok() returned false, return INTERRUPTED.
414-
return FutureReturnCode::INTERRUPTED;
374+
);
415375
}
416376

417377
/// Cancel any running spin* function, causing it to return.
@@ -420,7 +380,7 @@ class Executor
420380
* \throws std::runtime_error if there is an issue triggering the guard condition
421381
*/
422382
RCLCPP_PUBLIC
423-
void
383+
virtual void
424384
cancel();
425385

426386
/// Returns true if the executor is currently spinning.
@@ -433,6 +393,14 @@ class Executor
433393
is_spinning();
434394

435395
protected:
396+
/// Constructor that will not initialize any non-trivial members.
397+
/**
398+
* This constructor is intended to be used by any derived executor
399+
* that explicitly does not want to use the default implementation provided
400+
* by this class.
401+
*/
402+
explicit Executor(const std::shared_ptr<rclcpp::Context> & context);
403+
436404
/// Add a node to executor, execute the next available unit of work, and remove the node.
437405
/**
438406
* Implementation of spin_node_once using std::chrono::nanoseconds
@@ -447,6 +415,23 @@ class Executor
447415
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
448416
std::chrono::nanoseconds timeout);
449417

418+
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
419+
/**
420+
* \sa spin_until_future_complete()
421+
* The only difference with spin_until_future_complete() is that the future's
422+
* type is obscured through a std::function which lets you wait on it
423+
* reguardless of type.
424+
*
425+
* \param[in] timeout see spin_until_future_complete() for details
426+
* \param[in] wait_for_future function to wait on the future and get the
427+
* status after waiting
428+
*/
429+
RCLCPP_PUBLIC
430+
virtual FutureReturnCode
431+
spin_until_future_complete_impl(
432+
std::chrono::nanoseconds timeout,
433+
const std::function<std::future_status(std::chrono::nanoseconds wait_time)> & wait_for_future);
434+
450435
/// Collect work and execute available work, optionally within a duration.
451436
/**
452437
* Implementation of spin_some and spin_all.

rclcpp/src/rclcpp/clock.cpp

Lines changed: 49 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,10 @@ class Clock::Impl
4949

5050
rcl_clock_t rcl_clock_;
5151
rcl_allocator_t allocator_;
52+
bool stop_sleeping_ = false;
53+
bool shutdown_ = false;
54+
std::condition_variable cv_;
55+
std::mutex wait_mutex_;
5256
std::mutex clock_mutex_;
5357
};
5458

@@ -79,8 +83,20 @@ Clock::now() const
7983
return now;
8084
}
8185

86+
void
87+
Clock::cancel_sleep_or_wait()
88+
{
89+
{
90+
std::unique_lock lock(impl_->wait_mutex_);
91+
impl_->stop_sleeping_ = true;
92+
}
93+
impl_->cv_.notify_one();
94+
}
95+
8296
bool
83-
Clock::sleep_until(Time until, Context::SharedPtr context)
97+
Clock::sleep_until(
98+
Time until,
99+
Context::SharedPtr context)
84100
{
85101
if (!context || !context->is_valid()) {
86102
throw std::runtime_error("context cannot be slept with because it's invalid");
@@ -91,12 +107,14 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
91107
}
92108
bool time_source_changed = false;
93109

94-
std::condition_variable cv;
95-
96110
// Wake this thread if the context is shutdown
97111
rclcpp::OnShutdownCallbackHandle shutdown_cb_handle = context->add_on_shutdown_callback(
98-
[&cv]() {
99-
cv.notify_one();
112+
[this]() {
113+
{
114+
std::unique_lock lock(impl_->wait_mutex_);
115+
impl_->shutdown_ = true;
116+
}
117+
impl_->cv_.notify_one();
100118
});
101119
// No longer need the shutdown callback when this function exits
102120
auto callback_remover = rcpputils::scope_exit(
@@ -112,22 +130,24 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
112130
const std::chrono::steady_clock::time_point chrono_until =
113131
chrono_entry + std::chrono::nanoseconds(delta_t.nanoseconds());
114132

115-
// loop over spurious wakeups but notice shutdown
116-
std::unique_lock lock(impl_->clock_mutex_);
117-
while (now() < until && context->is_valid()) {
118-
cv.wait_until(lock, chrono_until);
133+
// loop over spurious wakeups but notice shutdown or stop of sleep
134+
std::unique_lock lock(impl_->wait_mutex_);
135+
while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid()) {
136+
impl_->cv_.wait_until(lock, chrono_until);
119137
}
138+
impl_->stop_sleeping_ = false;
120139
} else if (this_clock_type == RCL_SYSTEM_TIME) {
121140
auto system_time = std::chrono::system_clock::time_point(
122141
// Cast because system clock resolution is too big for nanoseconds on some systems
123142
std::chrono::duration_cast<std::chrono::system_clock::duration>(
124143
std::chrono::nanoseconds(until.nanoseconds())));
125144

126-
// loop over spurious wakeups but notice shutdown
127-
std::unique_lock lock(impl_->clock_mutex_);
128-
while (now() < until && context->is_valid()) {
129-
cv.wait_until(lock, system_time);
145+
// loop over spurious wakeups but notice shutdown or stop of sleep
146+
std::unique_lock lock(impl_->wait_mutex_);
147+
while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid()) {
148+
impl_->cv_.wait_until(lock, system_time);
130149
}
150+
impl_->stop_sleeping_ = false;
131151
} else if (this_clock_type == RCL_ROS_TIME) {
132152
// Install jump handler for any amount of time change, for two purposes:
133153
// - if ROS time is active, check if time reached on each new clock sample
@@ -139,11 +159,12 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
139159
threshold.min_forward.nanoseconds = 1;
140160
auto clock_handler = create_jump_callback(
141161
nullptr,
142-
[&cv, &time_source_changed](const rcl_time_jump_t & jump) {
162+
[this, &time_source_changed](const rcl_time_jump_t & jump) {
143163
if (jump.clock_change != RCL_ROS_TIME_NO_CHANGE) {
164+
std::lock_guard<std::mutex> lk(impl_->wait_mutex_);
144165
time_source_changed = true;
145166
}
146-
cv.notify_one();
167+
impl_->cv_.notify_one();
147168
},
148169
threshold);
149170

@@ -153,19 +174,25 @@ Clock::sleep_until(Time until, Context::SharedPtr context)
153174
std::chrono::duration_cast<std::chrono::system_clock::duration>(
154175
std::chrono::nanoseconds(until.nanoseconds())));
155176

156-
// loop over spurious wakeups but notice shutdown or time source change
157-
std::unique_lock lock(impl_->clock_mutex_);
158-
while (now() < until && context->is_valid() && !time_source_changed) {
159-
cv.wait_until(lock, system_time);
177+
// loop over spurious wakeups but notice shutdown, stop of sleep or time source change
178+
std::unique_lock lock(impl_->wait_mutex_);
179+
while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid() &&
180+
!time_source_changed)
181+
{
182+
impl_->cv_.wait_until(lock, system_time);
160183
}
184+
impl_->stop_sleeping_ = false;
161185
} else {
162186
// RCL_ROS_TIME with ros_time_is_active.
163187
// Just wait without "until" because installed
164188
// jump callbacks wake the cv on every new sample.
165-
std::unique_lock lock(impl_->clock_mutex_);
166-
while (now() < until && context->is_valid() && !time_source_changed) {
167-
cv.wait(lock);
189+
std::unique_lock lock(impl_->wait_mutex_);
190+
while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid() &&
191+
!time_source_changed)
192+
{
193+
impl_->cv_.wait(lock);
168194
}
195+
impl_->stop_sleeping_ = false;
169196
}
170197
}
171198

rclcpp/src/rclcpp/executor.cpp

Lines changed: 63 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,14 @@ static constexpr rclcpp::SubscriptionWaitSetMask kDefaultSubscriptionMask = {tru
5050

5151
class rclcpp::ExecutorImplementation {};
5252

53+
Executor::Executor(const std::shared_ptr<rclcpp::Context> & context)
54+
: spinning(false),
55+
entities_need_rebuild_(true),
56+
collector_(nullptr),
57+
wait_set_({}, {}, {}, {}, {}, {}, context)
58+
{
59+
}
60+
5361
Executor::Executor(const rclcpp::ExecutorOptions & options)
5462
: spinning(false),
5563
interrupt_guard_condition_(std::make_shared<rclcpp::GuardCondition>(options.context)),
@@ -120,7 +128,8 @@ Executor::~Executor()
120128
}
121129
}
122130

123-
void Executor::trigger_entity_recollect(bool notify)
131+
void
132+
Executor::trigger_entity_recollect(bool notify)
124133
{
125134
this->entities_need_rebuild_.store(true);
126135

@@ -240,6 +249,59 @@ Executor::spin_node_once_nanoseconds(
240249
this->remove_node(node, false);
241250
}
242251

252+
rclcpp::FutureReturnCode
253+
Executor::spin_until_future_complete_impl(
254+
std::chrono::nanoseconds timeout,
255+
const std::function<std::future_status(std::chrono::nanoseconds wait_time)> & wait_for_future)
256+
{
257+
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
258+
// inside a callback executed by an executor.
259+
260+
// Check the future before entering the while loop.
261+
// If the future is already complete, don't try to spin.
262+
std::future_status status = wait_for_future(std::chrono::seconds(0));
263+
if (status == std::future_status::ready) {
264+
return FutureReturnCode::SUCCESS;
265+
}
266+
267+
auto end_time = std::chrono::steady_clock::now();
268+
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
269+
timeout);
270+
if (timeout_ns > std::chrono::nanoseconds::zero()) {
271+
end_time += timeout_ns;
272+
}
273+
std::chrono::nanoseconds timeout_left = timeout_ns;
274+
275+
if (spinning.exchange(true)) {
276+
throw std::runtime_error("spin_until_future_complete() called while already spinning");
277+
}
278+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
279+
while (rclcpp::ok(this->context_) && spinning.load()) {
280+
// Do one item of work.
281+
spin_once_impl(timeout_left);
282+
283+
// Check if the future is set, return SUCCESS if it is.
284+
status = wait_for_future(std::chrono::seconds(0));
285+
if (status == std::future_status::ready) {
286+
return FutureReturnCode::SUCCESS;
287+
}
288+
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
289+
if (timeout_ns < std::chrono::nanoseconds::zero()) {
290+
continue;
291+
}
292+
// Otherwise check if we still have time to wait, return TIMEOUT if not.
293+
auto now = std::chrono::steady_clock::now();
294+
if (now >= end_time) {
295+
return FutureReturnCode::TIMEOUT;
296+
}
297+
// Subtract the elapsed time from the original timeout.
298+
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
299+
}
300+
301+
// The future did not complete before ok() returned false, return INTERRUPTED.
302+
return FutureReturnCode::INTERRUPTED;
303+
}
304+
243305
void
244306
Executor::spin_node_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node)
245307
{

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,10 @@ ament_add_gtest(test_client test_client.cpp)
5555
if(TARGET test_client)
5656
target_link_libraries(test_client ${PROJECT_NAME} mimick ${rcl_interfaces_TARGETS} ${test_msgs_TARGETS})
5757
endif()
58+
ament_add_gtest(test_clock test_clock.cpp)
59+
if(TARGET test_clock)
60+
target_link_libraries(test_clock ${PROJECT_NAME} mimick ${rcl_interfaces_TARGETS} ${test_msgs_TARGETS})
61+
endif()
5862
ament_add_gtest(test_copy_all_parameter_values test_copy_all_parameter_values.cpp)
5963
if(TARGET test_copy_all_parameter_values)
6064
target_link_libraries(test_copy_all_parameter_values ${PROJECT_NAME})

0 commit comments

Comments
 (0)