diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 3f03d069b..1cb9a0883 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -155,13 +155,20 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop) EXPECT_THAT(recorded_messages, SizeIs(expected_messages)); auto recorded_topics = mock_writer.get_topics(); - ASSERT_THAT(recorded_topics, SizeIs(1)) << "size=" << recorded_topics.size(); + EXPECT_THAT(recorded_topics, SizeIs(1)) << "size=" << recorded_topics.size(); + if (recorded_topics.size() != 1) { + for (const auto & topic : recorded_topics) { + std::cerr << "recorded topic name : " << topic.first << std::endl; + } + } EXPECT_THAT(recorded_topics.at(string_topic).first.serialization_format, Eq("rmw_format")); - ASSERT_THAT(recorded_messages, SizeIs(expected_messages)); - auto string_messages = filter_messages( - recorded_messages, string_topic); - ASSERT_THAT(string_messages, SizeIs(4)); - EXPECT_THAT(string_messages[0]->string_value, Eq(string_message->string_value)); + + auto string_messages = + filter_messages(recorded_messages, string_topic); + EXPECT_THAT(string_messages, SizeIs(4)); + for (const auto & str_msg : string_messages) { + EXPECT_THAT(str_msg->string_value, Eq(string_message->string_value)); + } } TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata)