Function ros2_medkit_integration_tests::run_demo_node
Defined in File demo_node_main.hpp
Function Documentation
Run a demo node with a graceful, race-free shutdown.
Integration-test shutdowns used to flake on a rotating cast of demo binaries with errors like:
“Unexpected condition: string capacity was zero for allocated data!
Exiting.” (rosidl_runtime_c / exit 255)
Root cause: rclcpp’s default SIGINT handler calls rclcpp::shutdown() asynchronously from a signal context, which invalidates the shared rcl context mid-run. An in-flight timer callback can then be holding a rosidl message whose string fields point at allocator state that is already partially torn down; destruction aborts.
Pattern used here (following “signalfd / sigwait thread” best practice):
Block SIGINT / SIGTERM in the main thread before any rclcpp work.
Call rclcpp::init with
SignalHandlerOptions::Noneso rclcpp does NOT install its own handlers on top.Construct the node + executor with signals still blocked.
Spawn a dedicated sigwait thread that blocks on sigwait() for SIGINT / SIGTERM and, on arrival, calls executor.cancel() to wake spin() from a known-good thread context.
executor.spin() returns cleanly; the main thread then removes the node from the executor and resets the shared_ptr while the rcl context is still valid. Message / publisher destructors therefore run against a consistent allocator and cannot trip the rosidl sequence-invariant abort.
rclcpp::shutdown() is called last, AFTER everything is destroyed.
Usage:
int main(int argc, char ** argv) { return ros2_medkit_integration_tests::run_demo_node(argc, argv, [] { return std::make_shared<MyDemoNode>(); }); }
The factory is called with signals already blocked and rclcpp::init already complete, so node constructors can create publishers / timers freely.