diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index 01fb7ae299..85013b62fc 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -145,6 +146,10 @@ class Recorder Recorder() { rclcpp::init(0, nullptr); + std::signal( + SIGTERM, [](int /* signal */) { + rclcpp::shutdown(); + }); } virtual ~Recorder() diff --git a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_unix.hpp b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_unix.hpp index f03e1c07f2..a1eb170d9f 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_unix.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_unix.hpp @@ -59,9 +59,9 @@ ProcessHandle start_execution(const std::string & command) return process_id; } -void stop_execution(const ProcessHandle & handle) +void stop_execution(const ProcessHandle & handle, int signum = SIGINT) { - killpg(handle, SIGINT); + killpg(handle, signum); int child_return_code; waitpid(handle, &child_return_code, 0); // this call will make sure that the process does execute without issues before it is killed by diff --git a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp index 98b4eabb34..ec21d01e31 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp @@ -21,6 +21,7 @@ #include #include +#include #include #include #include @@ -104,8 +105,10 @@ ProcessHandle start_execution(const std::string & command) return process; } -void stop_execution(const ProcessHandle & handle) +void stop_execution(const ProcessHandle & handle, int signum = SIGINT) { + // Match the Unix version by allowing for int signum argument - however Windows does not have + // Linux signals in the same way, so there isn't a 1:1 mapping to dispatch e.g. SIGTERM DWORD exit_code; GetExitCodeProcess(handle.process_info.hProcess, &exit_code); // 259 indicates that the process is still active: we want to make sure that the process is diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp index 1a039a41ab..763c5b826e 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp @@ -180,6 +180,20 @@ TEST_F(RecordFixture, record_end_to_end_test) { EXPECT_THAT(wrong_topic_messages, IsEmpty()); } +TEST_F(RecordFixture, record_end_to_end_exits_gracefully_on_sigterm) { + const std::string topic_name = "/test_sigterm"; + auto message = get_messages_strings()[0]; + message->string_value = "test"; + rosbag2_test_common::PublicationManager pub_manager; + pub_manager.setup_publisher(topic_name, message, 10); + auto process_handle = start_execution( + "ros2 bag record --output " + root_bag_path_.string() + " " + topic_name); + wait_for_db(); + pub_manager.run_publishers(); + stop_execution(process_handle, SIGTERM); + wait_for_metadata(); +} + // TODO(zmichaels11): Fix and enable this test on Windows. // This tests depends on the ability to read the metadata file. // Stopping the process on Windows does a hard kill and the metadata file is not written.