Skip to content

Commit 43d1297

Browse files
committed
fix(gateway): switch to MultiThreadedExecutor for thread-safe subscription creation
SingleThreadedExecutor does not synchronize Node::create_generic_subscription() called from external threads (cpp-httplib handlers) with its internal wait set iteration. This causes non-deterministic SIGSEGV on rolling where rclcpp internals are less forgiving of concurrent node manipulation. MultiThreadedExecutor properly synchronizes subscription lifecycle across threads. All gateway callbacks are already protected by mutexes (EntityCache, LogManager, TriggerManager, TriggerTopicSubscriber), so concurrent callback execution is safe. This is the definitive fix for the rolling SIGSEGV in test_data_read. The previous sampling_mutex_ + MutuallyExclusiveCallbackGroup fix reduced the race window but did not eliminate it.
1 parent 3af87b2 commit 43d1297

1 file changed

Lines changed: 8 additions & 1 deletion

File tree

src/ros2_medkit_gateway/src/main.cpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,14 @@ int main(int argc, char ** argv) {
2121

2222
auto node = std::make_shared<ros2_medkit_gateway::GatewayNode>();
2323

24-
rclcpp::spin(node);
24+
// MultiThreadedExecutor is required because cpp-httplib handler threads call
25+
// Node::create_generic_subscription() for topic sampling. SingleThreadedExecutor
26+
// does not synchronize external subscription creation with its internal iteration,
27+
// causing non-deterministic SIGSEGV on rolling. All gateway callbacks are already
28+
// protected by mutexes (EntityCache, LogManager, TriggerManager, etc.).
29+
rclcpp::executors::MultiThreadedExecutor executor;
30+
executor.add_node(node);
31+
executor.spin();
2532

2633
rclcpp::shutdown();
2734
return 0;

0 commit comments

Comments
 (0)