Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

If executor has been cancelled should not spin #2218

Closed
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
@@ -637,6 +637,9 @@ class Executor
/// Spinning state, used to prevent multi threaded calls to spin and to cancel blocking spins.
std::atomic_bool spinning;

/// Flag specifying that the executor has been cancelled and should not spin
std::atomic_bool executor_canceled{false};

/// Guard condition for signaling the rmw layer to wake up for special events.
std::shared_ptr<rclcpp::GuardCondition> interrupt_guard_condition_;

2 changes: 2 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
@@ -500,6 +500,8 @@ void
Executor::cancel()
{
spinning.store(false);
executor_canceled.store(true);

try {
interrupt_guard_condition_->trigger();
} catch (const rclcpp::exceptions::RCLError & ex) {
4 changes: 4 additions & 0 deletions rclcpp/src/rclcpp/executors/single_threaded_executor.cpp
Original file line number Diff line number Diff line change
@@ -27,6 +27,10 @@ SingleThreadedExecutor::~SingleThreadedExecutor() {}
void
SingleThreadedExecutor::spin()
{
if (executor_canceled.exchange(false)) {
return;
}

if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
Original file line number Diff line number Diff line change
@@ -41,6 +41,10 @@ StaticSingleThreadedExecutor::~StaticSingleThreadedExecutor()
void
StaticSingleThreadedExecutor::spin()
{
if (executor_canceled.exchange(false)) {
return;
}

if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
Original file line number Diff line number Diff line change
@@ -106,6 +106,10 @@ EventsExecutor::~EventsExecutor()
void
EventsExecutor::spin()
{
if (executor_canceled.exchange(false)) {
return;
}

if (spinning.exchange(true)) {
throw std::runtime_error("spin() called while already spinning");
}
19 changes: 19 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
@@ -373,6 +373,25 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout)
spinner.join();
}

TYPED_TEST(TestExecutors, testCancel)
{
using ExecutorType = TypeParam;
// rmw_connextdds doesn't support events-executor
if (
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0)
{
GTEST_SKIP();
}

ExecutorType executor;

auto executor_thread = std::thread([&](){ executor.spin();});
executor.cancel();
// This should not timeout
executor_thread.join();
}

class TestWaitable : public rclcpp::Waitable
{
public: