Skip to content

Commit 26d1468

Browse files
committed
Fix failing unittests: remove static executor
1 parent edf2605 commit 26d1468

File tree

3 files changed

+6
-7
lines changed

3 files changed

+6
-7
lines changed

core/src/introspection.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -79,8 +79,9 @@ class IntrospectionExecutor
7979
{
8080
public:
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

107108
class 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_;

core/test/test_move_relative.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,5 @@ int main(int argc, char** argv) {
133133
testing::InitGoogleTest(&argc, argv);
134134
rclcpp::init(argc, argv);
135135

136-
// Using quick_exit to avoid calling cleanup functions, which cause a segfault in rmw
137-
quick_exit(RUN_ALL_TESTS());
136+
return RUN_ALL_TESTS();
138137
}

visualization/motion_planning_tasks/test/test_task_model.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -239,6 +239,5 @@ int main(int argc, char** argv) {
239239
auto test_result = RUN_ALL_TESTS();
240240
app.exit(test_result);
241241
});
242-
// Using quick_exit to avoid calling cleanup functions, which cause a segfault in rmw
243-
quick_exit(app.exec());
242+
return app.exec();
244243
}

0 commit comments

Comments
 (0)