Skip to content
Merged
Show file tree
Hide file tree
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
2 changes: 1 addition & 1 deletion .github/workflows/run-pre-commit.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ jobs:

steps:
- name: Checkout repository
uses: actions/checkout@v2
uses: actions/checkout@v4

- name: Set up Python
uses: actions/setup-python@v4
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,13 @@ class ComponentManagerCallbackIsolated

struct ExecutorWrapper {
explicit ExecutorWrapper(std::shared_ptr<rclcpp::Executor> executor)
: executor(executor), thread_initialized(false) {}
: executor(executor) {}

ExecutorWrapper(const ExecutorWrapper &) = delete;
ExecutorWrapper &operator=(const ExecutorWrapper &) = delete;

std::shared_ptr<rclcpp::Executor> executor;
std::thread thread;
std::atomic_bool thread_initialized;
};

public:
Expand Down Expand Up @@ -176,7 +175,6 @@ void ComponentManagerCallbackIsolated::add_node_to_executor(uint64_t node_id) {
}
}

executor_wrapper.thread_initialized = true;
executor_wrapper.executor->spin();
});
} else {
Expand All @@ -199,7 +197,6 @@ void ComponentManagerCallbackIsolated::add_node_to_executor(uint64_t node_id) {
this->client_publisher_, tid, group_id);
}

executor_wrapper.thread_initialized = true;
executor_wrapper.executor->spin();
});
}
Expand All @@ -221,12 +218,18 @@ void ComponentManagerCallbackIsolated::remove_node_from_executor(

void ComponentManagerCallbackIsolated::cancel_executor(
ExecutorWrapper &executor_wrapper) {
if (!executor_wrapper.thread_initialized) {
auto context = this->get_node_base_interface()->get_context();
if (!executor_wrapper.thread.joinable()) {
return;
}

while (!executor_wrapper.executor->is_spinning() && rclcpp::ok(context)) {
rclcpp::sleep_for(std::chrono::milliseconds(1));
}
// Always wait for is_spinning() before cancel(). Do not use a separate
// "thread_initialized" flag as a fast-path: such a flag is set before spin()
// sets spinning=true, creating a window where cancel() has no effect and the
// subsequent spin() runs indefinitely, blocking join() forever.
auto context = this->get_node_base_interface()->get_context();

while (!executor_wrapper.executor->is_spinning() && rclcpp::ok(context)) {
rclcpp::sleep_for(std::chrono::milliseconds(1));
}

executor_wrapper.executor->cancel();
Expand Down
Loading