@@ -79,8 +79,9 @@ class IntrospectionExecutor
7979{
8080public:
8181 void add_node (const rclcpp::Node::SharedPtr& node) {
82- std::call_once (once_flag_, [this ] { executor_ = rclcpp::executors::SingleThreadedExecutor::make_unique (); });
8382 std::lock_guard<std::mutex> lock (mutex_);
83+ if (!executor_)
84+ executor_ = rclcpp::executors::SingleThreadedExecutor::make_unique ();
8485 executor_->add_node (node);
8586 if (nodes_count_++ == 0 )
8687 executor_thread_ = std::thread ([this ] { executor_->spin (); });
@@ -93,6 +94,7 @@ class IntrospectionExecutor
9394 executor_->cancel ();
9495 if (executor_thread_.joinable ())
9596 executor_thread_.join ();
97+ executor_.reset ();
9698 }
9799 }
98100
@@ -101,7 +103,6 @@ class IntrospectionExecutor
101103 std::thread executor_thread_;
102104 size_t nodes_count_ = 0 ;
103105 std::mutex mutex_;
104- std::once_flag once_flag_;
105106};
106107
107108class IntrospectionPrivate
@@ -157,7 +158,7 @@ class IntrospectionPrivate
157158 // / services to provide an individual Solution
158159 rclcpp::Service<moveit_task_constructor_msgs::srv::GetSolution>::SharedPtr get_solution_service_;
159160 rclcpp::Node::SharedPtr node_;
160- inline static IntrospectionExecutor executor_;
161+ IntrospectionExecutor executor_;
161162
162163 // / mapping from stages to their id
163164 std::map<const StagePrivate*, moveit_task_constructor_msgs::msg::StageStatistics::_id_type> stage_to_id_map_;
0 commit comments