Skip to content

Commit

Permalink
DRAFT: Fix: Double spin required since 28.2.0
Browse files Browse the repository at this point in the history
This is a first attempt to fix #2589. It passes all tests,
and seems to work, but I am 90% certain it introduces unwanted
races and lost wakeups.

Anyway, its a starting point for a discussion...
  • Loading branch information
Ubuntu committed Aug 2, 2024
1 parent 45adf65 commit a8144e7
Showing 1 changed file with 19 additions and 0 deletions.
19 changes: 19 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -726,6 +726,25 @@ Executor::wait_for_work(std::chrono::nanoseconds timeout)
{
TRACETOOLS_TRACEPOINT(rclcpp_executor_wait_for_work, timeout.count());

// the real one has been added to the main waitset, therefore we need to create a copy
executors::ExecutorNotifyWaitable::SharedPtr notify_cpy = std::make_shared<executors::ExecutorNotifyWaitable>(*notify_waitable_);

rclcpp::WaitSet notify_only_wait_set_({}, {}, {}, {}, {}, {}, context_);
notify_only_wait_set_.add_waitable(notify_cpy);
auto res = notify_only_wait_set_.wait(std::chrono::nanoseconds(0));
if(res.kind() == WaitResultKind::Ready) {
auto & rcl_wait_set = res.get_wait_set().get_rcl_wait_set();
if (notify_cpy->is_ready(rcl_wait_set)) {
notify_cpy->execute(notify_cpy->take_data());

// As this waitable is also used to signal
// a cancel, we need to check it here
if (!spinning.load()) {
return;
}
}
}

// Clear any previous wait result
this->wait_result_.reset();

Expand Down

0 comments on commit a8144e7

Please sign in to comment.