From 7d18f610c8cfa659a71dc6ff70eaa508f03f7197 Mon Sep 17 00:00:00 2001 From: evshary Date: Mon, 23 Sep 2019 17:28:26 +0800 Subject: [PATCH] Fix the test failure of wrong messages count Generate rclcpp::Node before start_recording since rclcpp::Node will set parameters of use_sim_time and publish message to parameter_events. This will cause the wrong messages count in the test. Signed-off-by: evshary --- .../test/rosbag2_transport/test_record_all_no_discovery.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp index 24840f3723..939ac5afe6 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp @@ -27,10 +27,11 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_ auto string_message = get_messages_strings()[0]; string_message->string_value = "Hello World"; + auto publisher_node = std::make_shared("publisher_for_test"); + start_recording({true, true, {}, "rmw_format", 1ms}); std::this_thread::sleep_for(100ms); - auto publisher_node = std::make_shared("publisher_for_test"); auto publisher = publisher_node->create_publisher("/string_topic", 10); for (int i = 0; i < 5; ++i) { std::this_thread::sleep_for(20ms);