@@ -38,6 +38,16 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager
3838 {
3939 std::shared_ptr<rclcpp::Executor> executor;
4040 std::thread thread;
41+ std::atomic_bool thread_initialized;
42+
43+ // / Constructor for the wrapper.
44+ // / This is necessary as atomic variables don't have copy/move operators
45+ // / implemented so this structure is not copyable/movable by default
46+ explicit DedicatedExecutorWrapper (std::shared_ptr<rclcpp::Executor> exec)
47+ : executor(exec),
48+ thread_initialized(false )
49+ {
50+ }
4151 };
4252
4353public:
@@ -59,15 +69,19 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager
5969 void
6070 add_node_to_executor (uint64_t node_id) override
6171 {
62- DedicatedExecutorWrapper executor_wrapper;
6372 auto exec = std::make_shared<ExecutorT>();
6473 exec->add_node (node_wrappers_[node_id].get_node_base_interface ());
65- executor_wrapper.executor = exec;
66- executor_wrapper.thread = std::thread (
67- [exec]() {
74+
75+ // Emplace rather than std::move since move operations are deleted for atomics
76+ auto result = dedicated_executor_wrappers_.emplace (std::make_pair (node_id, exec));
77+ DedicatedExecutorWrapper & wrapper = result.first ->second ;
78+ wrapper.executor = exec;
79+ auto & thread_initialized = wrapper.thread_initialized ;
80+ wrapper.thread = std::thread (
81+ [exec, &thread_initialized]() {
82+ thread_initialized = true ;
6883 exec->spin ();
6984 });
70- dedicated_executor_wrappers_[node_id] = std::move (executor_wrapper);
7185 }
7286 // / Remove component node from executor model, it's invoked in on_unload_node()
7387 /* *
@@ -90,15 +104,21 @@ class ComponentManagerIsolated : public rclcpp_components::ComponentManager
90104 */
91105 void cancel_executor (DedicatedExecutorWrapper & executor_wrapper)
92106 {
93- // We can't immediately call the cancel() API on an executor because if it is not
94- // already spinning, this operation will have no effect.
95- // We rely on the assumption that this class creates executors and then immediately makes them
96- // spin in a separate thread, i.e. the time gap between when the executor is created and when
97- // it starts to spin is small (although it's not negligible).
98-
99- while (!executor_wrapper.executor ->is_spinning ()) {
100- // This is an arbitrarily small delay to avoid busy looping
101- rclcpp::sleep_for (std::chrono::milliseconds (1 ));
107+ // Verify that the executor thread has begun spinning.
108+ // If it has not, then wait until the thread starts to ensure
109+ // that cancel() will fully stop the execution
110+ //
111+ // This prevents a previous race condition that occurs between the
112+ // creation of the executor spin thread and cancelling an executor
113+
114+ if (!executor_wrapper.thread_initialized ) {
115+ auto context = this ->get_node_base_interface ()->get_context ();
116+
117+ // Guarantee that either the executor is spinning or we are shutting down.
118+ while (!executor_wrapper.executor ->is_spinning () && rclcpp::ok (context)) {
119+ // This is an arbitrarily small delay to avoid busy looping
120+ rclcpp::sleep_for (std::chrono::milliseconds (1 ));
121+ }
102122 }
103123
104124 // After the while loop we are sure that the executor is now spinning, so
0 commit comments