From c551f87ce279337580bd3a27edd8e81538a0656f Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Sun, 5 Nov 2023 00:38:02 -0700 Subject: [PATCH 1/8] Address flakiness in newly added rosbag2_transport tests - Got rid form ambient sleep for waiting for messages to be recorded - Exclude "/rosout" topic from recording Signed-off-by: Michael Orlov --- .../rosbag2_transport/test_record_all.cpp | 41 ++++++++++--------- .../rosbag2_transport/test_record_regex.cpp | 26 +++++++++--- 2 files changed, 42 insertions(+), 25 deletions(-) diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index 6680aa754b..2b818fd044 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -50,7 +50,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are pub_manager.setup_publisher(string_topic, string_message, 2); rosbag2_transport::RecordOptions record_options = - {true, false, false, {}, {}, {}, {}, "rmw_format", 100ms}; + {true, false, false, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -63,8 +63,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are pub_manager.run_publishers(); auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( @@ -72,11 +71,9 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are [&mock_writer, &expected_messages]() { return mock_writer.get_messages().size() >= expected_messages; }); - auto recorded_messages = mock_writer.get_messages(); - // We may receive additional messages from rosout, it doesn't matter, - // as long as we have received at least as many total messages as we expect EXPECT_TRUE(ret) << "failed to capture expected messages in time"; - EXPECT_THAT(recorded_messages, SizeIs(Ge(expected_messages))); + auto recorded_messages = mock_writer.get_messages(); + EXPECT_EQ(recorded_messages.size(), expected_messages); auto string_messages = filter_messages( recorded_messages, string_topic); @@ -100,7 +97,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a "test_service_2"); rosbag2_transport::RecordOptions record_options = - {false, true, false, {}, {}, {}, {}, "rmw_format", 100ms}; + {false, true, false, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -111,18 +108,21 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a ASSERT_TRUE(client_manager_2->check_service_ready()); - // By default, only client introspection is enable. + // By default, only client introspection is enabled. // For one request, service event topic get 2 messages. ASSERT_TRUE(client_manager_1->send_request()); ASSERT_TRUE(client_manager_2->send_request()); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); size_t expected_messages = 4; + auto ret = rosbag2_test_common::wait_until_shutdown( + std::chrono::seconds(5), + [&mock_writer, &expected_messages]() { + return mock_writer.get_messages().size() >= expected_messages; + }); + EXPECT_TRUE(ret) << "failed to capture expected messages in time"; auto recorded_messages = mock_writer.get_messages(); EXPECT_EQ(recorded_messages.size(), expected_messages); } @@ -140,7 +140,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a pub_manager.setup_publisher(string_topic, string_message, 1); rosbag2_transport::RecordOptions record_options = - {true, true, false, {}, {}, {"rosout"}, {}, "rmw_format", 100ms}; + {true, true, false, {}, {}, {"/rosout"}, {}, "rmw_format", 100ms}; auto recorder = std::make_shared( std::move(writer_), storage_options_, record_options); recorder->record(); @@ -153,17 +153,20 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a pub_manager.run_publishers(); - // By default, only client introspection is enable. + // By default, only client introspection is enabled. // For one request, service event topic get 2 messages. ASSERT_TRUE(client_manager_1->send_request()); - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); size_t expected_messages = 3; + auto ret = rosbag2_test_common::wait_until_shutdown( + std::chrono::seconds(5), + [&mock_writer, &expected_messages]() { + return mock_writer.get_messages().size() >= expected_messages; + }); + EXPECT_TRUE(ret) << "failed to capture expected messages in time"; auto recorded_messages = mock_writer.get_messages(); EXPECT_EQ(recorded_messages.size(), expected_messages); } diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp index 1d154c32be..70511f7b34 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp @@ -303,16 +303,23 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) ASSERT_TRUE(service_manager_b2->check_service_ready()); auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); ASSERT_TRUE(service_manager_v1->send_request()); ASSERT_TRUE(service_manager_v2->send_request()); ASSERT_TRUE(service_manager_e1->send_request()); ASSERT_TRUE(service_manager_b1->send_request()); ASSERT_TRUE(service_manager_b2->send_request()); + + size_t expected_messages = 4; + auto ret = rosbag2_test_common::wait_until_shutdown( + std::chrono::seconds(5), + [&mock_writer, &expected_messages]() { + return mock_writer.get_messages().size() >= expected_messages; + }); + EXPECT_TRUE(ret) << "failed to capture expected messages in time"; auto recorded_messages = mock_writer.get_messages(); - EXPECT_THAT(recorded_messages, SizeIs(4)); + EXPECT_THAT(recorded_messages, SizeIs(expected_messages)); auto recorded_topics = mock_writer.get_topics(); EXPECT_THAT(recorded_topics, SizeIs(2)); @@ -369,16 +376,23 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording ASSERT_TRUE(service_manager_b2->check_service_ready()); auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); ASSERT_TRUE(service_manager_v1->send_request()); ASSERT_TRUE(service_manager_v2->send_request()); ASSERT_TRUE(service_manager_e1->send_request()); ASSERT_TRUE(service_manager_b1->send_request()); ASSERT_TRUE(service_manager_b2->send_request()); + + size_t expected_messages = 4; + auto ret = rosbag2_test_common::wait_until_shutdown( + std::chrono::seconds(5), + [&mock_writer, &expected_messages]() { + return mock_writer.get_messages().size() >= expected_messages; + }); + EXPECT_TRUE(ret) << "failed to capture expected messages in time"; auto recorded_messages = mock_writer.get_messages(); - EXPECT_THAT(recorded_messages, SizeIs(4)); + EXPECT_THAT(recorded_messages, SizeIs(expected_messages)); auto recorded_topics = mock_writer.get_topics(); EXPECT_THAT(recorded_topics, SizeIs(2)); From 9e637f1e047eb44ac11a1057151349eeca355da9 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Mon, 6 Nov 2023 23:58:02 -0800 Subject: [PATCH 2/8] Use wait_for_srvice_to_be_ready() instead check_service_ready() - Also add default timeout parameter for ClientManager::send_request(..) Signed-off-by: Michael Orlov --- .../rosbag2_test_common/client_manager.hpp | 14 +++++++++++-- .../rosbag2_transport/test_record_all.cpp | 7 +++---- .../rosbag2_transport/test_record_regex.cpp | 20 +++++++++---------- 3 files changed, 25 insertions(+), 16 deletions(-) diff --git a/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp b/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp index a7764b4e49..958506758f 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp @@ -89,7 +89,17 @@ class ClientManager : public rclcpp::Node return true; } - bool send_request() + bool wait_for_srvice_to_be_ready(std::chrono::duration timeout = std::chrono::seconds(5)) + { + using clock = std::chrono::system_clock; + auto start = clock::now(); + while (!check_service_ready() && (clock::now() - start) < timeout) { + std::this_thread::sleep_for(std::chrono::milliseconds(25)); + } + return check_service_ready(); + } + + bool send_request(std::chrono::duration timeout = std::chrono::seconds(5)) { if (!check_service_ready()) { return false; @@ -100,7 +110,7 @@ class ClientManager : public rclcpp::Node auto result = client->async_send_request(request); // Wait for the result. if (rclcpp::executors::spin_node_until_future_complete( - exec_, get_node_base_interface(), result) != rclcpp::FutureReturnCode::SUCCESS) + exec_, get_node_base_interface(), result, timeout) != rclcpp::FutureReturnCode::SUCCESS) { RCLCPP_INFO( rclcpp::get_logger("service_client_manager"), "Failed to get response !"); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index 2b818fd044..585ab0776a 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -104,9 +104,8 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a start_async_spin(recorder); - ASSERT_TRUE(client_manager_1->check_service_ready()); - - ASSERT_TRUE(client_manager_2->check_service_ready()); + ASSERT_TRUE(client_manager_1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(client_manager_2->wait_for_srvice_to_be_ready()); // By default, only client introspection is enabled. // For one request, service event topic get 2 messages. @@ -149,7 +148,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str())); - ASSERT_TRUE(client_manager_1->check_service_ready()); + ASSERT_TRUE(client_manager_1->wait_for_srvice_to_be_ready()); pub_manager.run_publishers(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp index 70511f7b34..45e3a7bf08 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp @@ -296,11 +296,11 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) start_async_spin(recorder); - ASSERT_TRUE(service_manager_v1->check_service_ready()); - ASSERT_TRUE(service_manager_v2->check_service_ready()); - ASSERT_TRUE(service_manager_e1->check_service_ready()); - ASSERT_TRUE(service_manager_b1->check_service_ready()); - ASSERT_TRUE(service_manager_b2->check_service_ready()); + ASSERT_TRUE(service_manager_v1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_v2->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_e1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_b1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_b2->wait_for_srvice_to_be_ready()); auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); @@ -369,11 +369,11 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording start_async_spin(recorder); - ASSERT_TRUE(service_manager_v1->check_service_ready()); - ASSERT_TRUE(service_manager_v2->check_service_ready()); - ASSERT_TRUE(service_manager_e1->check_service_ready()); - ASSERT_TRUE(service_manager_b1->check_service_ready()); - ASSERT_TRUE(service_manager_b2->check_service_ready()); + ASSERT_TRUE(service_manager_v1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_v2->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_e1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_b1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_manager_b2->wait_for_srvice_to_be_ready()); auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); From 96096ff677a4ca47280a1bf8f5f69e512f7ac3be Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 00:05:05 -0800 Subject: [PATCH 3/8] Add rosbag2_test_common::wait_until_condition(..) Signed-off-by: Michael Orlov --- .../include/rosbag2_test_common/wait_for.hpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/rosbag2_test_common/include/rosbag2_test_common/wait_for.hpp b/rosbag2_test_common/include/rosbag2_test_common/wait_for.hpp index d8406c286b..9578e72439 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/wait_for.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/wait_for.hpp @@ -51,6 +51,23 @@ bool wait_until_shutdown(Timeout timeout, Condition condition) rclcpp::shutdown(); return true; } + +template +bool wait_until_condition( + Condition condition, + std::chrono::duration timeout = std::chrono::seconds(5)) +{ + using clock = std::chrono::system_clock; + auto start = clock::now(); + while (!condition()) { + if ((clock::now() - start) > timeout) { + return false; + } + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + return true; +} + } // namespace rosbag2_test_common #endif // ROSBAG2_TEST_COMMON__WAIT_FOR_HPP_ From 01a48c3013106bda72288ad604f22d2912587e54 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 00:09:10 -0800 Subject: [PATCH 4/8] Rewrite get_service_info tests to be more deterministic - Also parameterize tests to use default supported storage plugins Signed-off-by: Michael Orlov --- rosbag2_tests/CMakeLists.txt | 1 + rosbag2_tests/package.xml | 1 + .../test_rosbag2_info_get_service_info.cpp | 368 +++++++++++------- 3 files changed, 231 insertions(+), 139 deletions(-) diff --git a/rosbag2_tests/CMakeLists.txt b/rosbag2_tests/CMakeLists.txt index 664e6ab747..c9aecb9e44 100644 --- a/rosbag2_tests/CMakeLists.txt +++ b/rosbag2_tests/CMakeLists.txt @@ -129,6 +129,7 @@ if(BUILD_TESTING) rosbag2_cpp::rosbag2_cpp rosbag2_storage::rosbag2_storage rosbag2_test_common::rosbag2_test_common + rosbag2_transport::rosbag2_transport ${test_msgs_TARGETS} ) endif() diff --git a/rosbag2_tests/package.xml b/rosbag2_tests/package.xml index cbbfe413f2..8d9404100e 100644 --- a/rosbag2_tests/package.xml +++ b/rosbag2_tests/package.xml @@ -28,6 +28,7 @@ rosbag2_storage_default_plugins rosbag2_storage rosbag2_test_common + rosbag2_transport std_msgs test_msgs diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp index 6cac3813a6..2e268ad6d5 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Sony Group Corporation. +// Copyright 2023 Sony Group Corporation and Apex.AI, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -21,226 +21,316 @@ #include "rosbag2_cpp/writer.hpp" #include "rosbag2_test_common/client_manager.hpp" -#include "rosbag2_test_common/process_execution_helpers.hpp" #include "rosbag2_test_common/publication_manager.hpp" #include "rosbag2_test_common/temporary_directory_fixture.hpp" +#include "rosbag2_test_common/tested_storage_ids.hpp" +#include "rosbag2_test_common/wait_for.hpp" + +#include "rosbag2_transport/recorder.hpp" #include "test_msgs/message_fixtures.hpp" #include "test_msgs/msg/basic_types.hpp" #include "test_msgs/srv/basic_types.hpp" -class GetServiceInfoTest : public rosbag2_test_common::TemporaryDirectoryFixture +class SequentialWriterForTest : public rosbag2_cpp::writers::SequentialWriter +{ +public: + size_t get_number_of_written_messages() + { + size_t num_messages = 0; + for (const auto & file : metadata_.files) { + num_messages += file.message_count; + } + return num_messages; + } +}; + +class GetServiceInfoTest : public rosbag2_test_common::ParametrizedTemporaryDirectoryFixture { public: void SetUp() override { - rclcpp::init(0, nullptr); + auto bag_name = get_test_name() + "_" + GetParam(); + root_bag_path_ = rcpputils::fs::path(temporary_dir_path_) / bag_name; + + // Clean up potentially leftover bag files. + // There may be leftovers if the system reallocates a temp directory + // used by a previous test execution and the test did not have a clean exit. + rcpputils::fs::remove_all(root_bag_path_); } void TearDown() override + { + rcpputils::fs::remove_all(root_bag_path_); + } + + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + static void TearDownTestCase() { rclcpp::shutdown(); } - rcpputils::fs::path get_bag_path() + template + void start_async_spin(T node) { - return rcpputils::fs::path(temporary_dir_path_) / - UnitTest::GetInstance()->current_test_info()->name(); + node_spinner_future_ = std::async( + std::launch::async, + [&]() -> void { + rclcpp::executors::SingleThreadedExecutor exec; + exec.add_node(node); + while (!exit_from_node_spinner_) { + exec.spin_some(); + } + }); } - const std::string get_bag_file_name(int split_index, std::string storage_id) + void stop_spinning() { - if (storage_id == "mcap") { - return std::string(UnitTest::GetInstance()->current_test_info()->name()) + - "_" + std::to_string(split_index) + ".mcap"; - } else if (storage_id == "sqlite3") { - return std::string(UnitTest::GetInstance()->current_test_info()->name()) + - "_" + std::to_string(split_index) + ".db3"; - } else { - throw std::runtime_error("Invalid storage id : \"" + storage_id + "\""); + exit_from_node_spinner_ = true; + if (node_spinner_future_.valid()) { + node_spinner_future_.wait(); } } - void wait_for_storage_file( - std::string file_path, - std::chrono::duration timeout = std::chrono::seconds(10)) + std::string get_test_name() const + { + const auto * test_info = UnitTest::GetInstance()->current_test_info(); + std::string test_name = test_info->name(); + // Replace any slashes in the test name, since it is used in paths + std::replace(test_name.begin(), test_name.end(), '/', '_'); + return test_name; + } + + std::string get_bag_file_name(int split_index = 0) const + { + const auto storage_id = GetParam(); + std::stringstream bag_file_name; + bag_file_name << get_test_name() << "_" << storage_id << "_" << split_index; + return rosbag2_test_common::bag_filename_for_storage_id(bag_file_name.str(), storage_id); + } + + std::string get_bag_path_str() const + { + return root_bag_path_.string(); + } + + bool wait_for_subscriptions( + const rosbag2_transport::Recorder & recorder, + const std::vector && topic_names, + std::chrono::duration timeout = std::chrono::seconds(5)) { - auto check_file_path = rcpputils::fs::path(file_path); - const auto start_time = std::chrono::steady_clock::now(); - while (std::chrono::steady_clock::now() - start_time < timeout) { - if (check_file_path.exists()) { - return; + using clock = std::chrono::system_clock; + auto start = clock::now(); + bool ready = false; + while (!ready && (clock::now() - start) < timeout) { + const auto & subscriptions = recorder.subscriptions(); + ready = true; + for (const auto & topic_name : topic_names) { + if (subscriptions.find(topic_name) == subscriptions.end()) { + ready = false; + break; + } } - std::this_thread::sleep_for(std::chrono::milliseconds(50)); + std::this_thread::sleep_for(std::chrono::milliseconds(25)); } - ASSERT_EQ(check_file_path.exists(), true) - << "Could not find storage file: \"" << check_file_path.string() << "\""; + return ready; } - void topics_and_services_bag_test(std::string storage_id); + // relative path to the root of the bag file. + rcpputils::fs::path root_bag_path_; + std::future node_spinner_future_; + std::atomic_bool exit_from_node_spinner_{false}; }; -TEST_F(GetServiceInfoTest, only_topics_bag_test) { - const std::string storage_id = "mcap"; - const auto bag_path = get_bag_path(); - +TEST_P(GetServiceInfoTest, only_topics_bag_test) { + const std::string storage_id = GetParam(); + const auto bag_path_str = get_bag_path_str(); { // Create an empty bag with default storage rosbag2_cpp::Writer writer; rosbag2_storage::StorageOptions storage_options; storage_options.storage_id = storage_id; - storage_options.uri = bag_path.string(); + storage_options.uri = bag_path_str; writer.open(storage_options); test_msgs::msg::BasicTypes msg; writer.write(msg, "test_topic", rclcpp::Time{}); } - std::string first_storage_file_path; - { - rosbag2_storage::MetadataIo metadata_io; - auto metadata = metadata_io.read_metadata(bag_path.string()); - first_storage_file_path = (bag_path / metadata.relative_file_paths[0]).string(); - } rosbag2_cpp::Info info; - std::vector> ret_service_info; - - ASSERT_NO_THROW(ret_service_info = info.read_service_info(first_storage_file_path, storage_id)); + std::vector> ret_service_infos; + const std::string recorded_bag_uri = bag_path_str + "/" + get_bag_file_name(); + ASSERT_NO_THROW(ret_service_infos = info.read_service_info(recorded_bag_uri, storage_id)) << + recorded_bag_uri; - EXPECT_TRUE(ret_service_info.empty()); + EXPECT_TRUE(ret_service_infos.empty()); } -TEST_F(GetServiceInfoTest, only_services_bag_test) { - const std::string storage_id = "mcap"; - const auto bag_path = get_bag_path(); - const std::string record_cmd = "ros2 bag record --all-services -o " + bag_path.string(); - std::string bag_filename; - - ASSERT_NO_THROW(bag_filename = get_bag_file_name(0, storage_id)); +TEST_P(GetServiceInfoTest, only_services_bag_test) { + const std::string storage_id = GetParam(); + const std::string bag_path_str = get_bag_path_str(); auto service_client_manager = std::make_shared>( "test_service"); - if (!service_client_manager->check_service_ready()) { - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - ASSERT_TRUE(service_client_manager->check_service_ready()); - } + std::unique_ptr writer_impl = + std::make_unique(); + auto writer = std::make_unique(std::move(writer_impl)); + + rosbag2_storage::StorageOptions storage_options; + storage_options.storage_id = storage_id; + storage_options.uri = bag_path_str; + rosbag2_transport::RecordOptions record_options = + {false, true, false, {}, {}, {"/rosout"}, {}, "cdr", 100ms}; + auto recorder = std::make_shared( + std::move(writer), storage_options, record_options); + recorder->record(); - auto record_process = start_execution(record_cmd); + start_async_spin(recorder); auto cleanup_process_handle = rcpputils::make_scope_exit( - [record_process]() { - stop_execution(record_process); - }); + [&]() {stop_spinning();}); - wait_for_storage_file(bag_path.string() + "/" + bag_filename); + ASSERT_TRUE(service_client_manager->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(wait_for_subscriptions(*recorder, {"/test_service/_service_event"})); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - ASSERT_TRUE(service_client_manager->send_request()); - ASSERT_TRUE(service_client_manager->send_request()); - ASSERT_TRUE(service_client_manager->send_request()); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); + constexpr size_t num_service_requests = 3; + for (size_t i = 0; i < num_service_requests; i++) { + ASSERT_TRUE(service_client_manager->send_request()); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } - stop_execution(record_process); + auto & writer_ref = recorder->get_writer_handle(); + auto & recorder_writer = + dynamic_cast(writer_ref.get_implementation_handle()); + + // By default, only client introspection is enabled. + // For one request, service event topic get 2 messages. + size_t expected_messages = num_service_requests * 2; + auto ret = rosbag2_test_common::wait_until_condition( + [&recorder_writer, &expected_messages]() { + return recorder_writer.get_number_of_written_messages() >= expected_messages; + }, + std::chrono::seconds(5)); + EXPECT_TRUE(ret) << "Failed to capture " << expected_messages << " expected messages in time"; + + recorder->stop(); + stop_spinning(); cleanup_process_handle.cancel(); rosbag2_cpp::Info info; - std::vector> ret_service_info; - - ASSERT_NO_THROW( - ret_service_info = - info.read_service_info(bag_path.string() + "/" + bag_filename, storage_id)); - - ASSERT_EQ(ret_service_info.size(), 1); - EXPECT_EQ(ret_service_info[0]->name, "/test_service"); - EXPECT_EQ(ret_service_info[0]->type, "test_msgs/srv/BasicTypes"); - EXPECT_EQ(ret_service_info[0]->request_count, 3); - EXPECT_EQ(ret_service_info[0]->response_count, 3); - EXPECT_EQ(ret_service_info[0]->serialization_format, "cdr"); + std::vector> ret_service_infos; + + const std::string recorded_bag_uri = bag_path_str + "/" + get_bag_file_name(); + ASSERT_NO_THROW(ret_service_infos = info.read_service_info(recorded_bag_uri, storage_id)) << + recorded_bag_uri; + + ASSERT_EQ(ret_service_infos.size(), 1); + EXPECT_EQ(ret_service_infos[0]->name, "/test_service"); + EXPECT_EQ(ret_service_infos[0]->type, "test_msgs/srv/BasicTypes"); + EXPECT_EQ(ret_service_infos[0]->request_count, num_service_requests); + EXPECT_EQ(ret_service_infos[0]->response_count, num_service_requests); + EXPECT_EQ(ret_service_infos[0]->serialization_format, "cdr"); } -void GetServiceInfoTest::topics_and_services_bag_test(std::string storage_id) -{ - const auto bag_path = get_bag_path(); - const std::string record_cmd = - "ros2 bag record --all-topics --all-services -s " + storage_id + " -o " + bag_path.string(); - std::string bag_filename; - - ASSERT_NO_THROW(bag_filename = get_bag_file_name(0, storage_id)); +TEST_P(GetServiceInfoTest, topics_and_services_bag_test) { + const std::string storage_id = GetParam(); + const std::string bag_path_str = get_bag_path_str(); // Prepare service/client auto service_client_manager1 = std::make_shared>( "test_service1"); - - if (!service_client_manager1->check_service_ready()) { - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - ASSERT_TRUE(service_client_manager1->check_service_ready()); - } - auto service_client_manager2 = std::make_shared>( "test_service2"); - if (!service_client_manager2->check_service_ready()) { - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - ASSERT_TRUE(service_client_manager2->check_service_ready()); - } + ASSERT_TRUE(service_client_manager1->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_client_manager2->wait_for_srvice_to_be_ready()); rosbag2_test_common::PublicationManager pub_manager; auto message = get_messages_strings()[0]; pub_manager.setup_publisher("test_topic1", message, 1); pub_manager.setup_publisher("test_topic2", message, 1); - auto record_process = start_execution(record_cmd); + std::unique_ptr writer_impl = + std::make_unique(); + auto writer = std::make_unique(std::move(writer_impl)); + rosbag2_storage::StorageOptions storage_options; + storage_options.storage_id = storage_id; + storage_options.uri = bag_path_str; + rosbag2_transport::RecordOptions record_options = + {true, true, false, {}, {}, {"/rosout"}, {}, "cdr", 100ms}; + auto recorder = std::make_shared( + std::move(writer), storage_options, record_options); + recorder->record(); + + start_async_spin(recorder); auto cleanup_process_handle = rcpputils::make_scope_exit( - [record_process]() { - stop_execution(record_process); - }); - - wait_for_storage_file(bag_path.string() + "/" + bag_filename); - - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - ASSERT_TRUE(service_client_manager1->send_request()); - ASSERT_TRUE(service_client_manager1->send_request()); - ASSERT_TRUE(service_client_manager2->send_request()); + [&]() {stop_spinning();}); + + ASSERT_TRUE( + wait_for_subscriptions( + *recorder, + {"/test_service1/_service_event", + "/test_service2/_service_event", + "/test_topic1", + "/test_topic2"} + ) + ); + + constexpr size_t num_service_requests = 2; + for (size_t i = 0; i < num_service_requests; i++) { + ASSERT_TRUE(service_client_manager1->send_request()); + ASSERT_TRUE(service_client_manager2->send_request()); + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } pub_manager.run_publishers(); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - stop_execution(record_process); + auto & writer_ref = recorder->get_writer_handle(); + auto & recorder_writer = + dynamic_cast(writer_ref.get_implementation_handle()); + + // By default, only client introspection is enabled. + // For one request, service event topic get 2 messages. + size_t expected_messages = num_service_requests * 2 + 2; + auto ret = rosbag2_test_common::wait_until_condition( + [&recorder_writer, &expected_messages]() { + return recorder_writer.get_number_of_written_messages() >= expected_messages; + }, + std::chrono::seconds(5)); + EXPECT_TRUE(ret) << "Failed to capture " << expected_messages << " expected messages in time"; + + recorder->stop(); + stop_spinning(); cleanup_process_handle.cancel(); rosbag2_cpp::Info info; - std::vector> ret_service_info; - - ASSERT_NO_THROW( - ret_service_info = - info.read_service_info(bag_path.string() + "/" + bag_filename, storage_id)); - - ASSERT_EQ(ret_service_info.size(), 2); - if (ret_service_info[0]->name == "/test_service2") { - EXPECT_EQ(ret_service_info[0]->request_count, 1); - EXPECT_EQ(ret_service_info[0]->response_count, 1); - EXPECT_EQ(ret_service_info[1]->name, "/test_service1"); - EXPECT_EQ(ret_service_info[1]->request_count, 2); - EXPECT_EQ(ret_service_info[1]->response_count, 2); + std::vector> ret_service_infos; + + const std::string recorded_bag_uri = bag_path_str + "/" + get_bag_file_name(); + ASSERT_NO_THROW(ret_service_infos = info.read_service_info(recorded_bag_uri, storage_id)) << + recorded_bag_uri; + ASSERT_EQ(ret_service_infos.size(), 2); + if (ret_service_infos[0]->name == "/test_service2") { + EXPECT_EQ(ret_service_infos[1]->name, "/test_service1"); } else { - EXPECT_EQ(ret_service_info[0]->name, "/test_service1"); - EXPECT_EQ(ret_service_info[0]->request_count, 2); - EXPECT_EQ(ret_service_info[0]->response_count, 2); - EXPECT_EQ(ret_service_info[1]->name, "/test_service2"); - EXPECT_EQ(ret_service_info[1]->request_count, 1); - EXPECT_EQ(ret_service_info[1]->response_count, 1); - } - EXPECT_EQ(ret_service_info[0]->type, "test_msgs/srv/BasicTypes"); - EXPECT_EQ(ret_service_info[0]->serialization_format, "cdr"); - EXPECT_EQ(ret_service_info[1]->type, "test_msgs/srv/BasicTypes"); - EXPECT_EQ(ret_service_info[1]->serialization_format, "cdr"); -} - -TEST_F(GetServiceInfoTest, topics_and_services_mcap_bag_test) { - topics_and_services_bag_test("mcap"); + EXPECT_EQ(ret_service_infos[0]->name, "/test_service1"); + EXPECT_EQ(ret_service_infos[1]->name, "/test_service2"); + } + for (const auto & service_info : ret_service_infos) { + EXPECT_EQ(service_info->request_count, num_service_requests); + EXPECT_EQ(service_info->response_count, num_service_requests); + EXPECT_EQ(service_info->type, "test_msgs/srv/BasicTypes"); + EXPECT_EQ(service_info->serialization_format, "cdr"); + } } -TEST_F(GetServiceInfoTest, topics_and_services_sqlite3_bag_test) { - topics_and_services_bag_test("sqlite3"); -} +INSTANTIATE_TEST_SUITE_P( + TestInfoGetServiceInfo, + GetServiceInfoTest, + ::testing::ValuesIn(rosbag2_test_common::kTestedStorageIDs) +); From ef4c2c4c117676d1899e625ce94ecfd3037488d5 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 00:21:31 -0800 Subject: [PATCH 5/8] Renames in the get_service_info tests Signed-off-by: Michael Orlov --- rosbag2_tests/CMakeLists.txt | 8 ++++---- ...info.cpp => test_rosbag2_cpp_get_service_info.cpp} | 11 ++++++----- 2 files changed, 10 insertions(+), 9 deletions(-) rename rosbag2_tests/test/rosbag2_tests/{test_rosbag2_info_get_service_info.cpp => test_rosbag2_cpp_get_service_info.cpp} (96%) diff --git a/rosbag2_tests/CMakeLists.txt b/rosbag2_tests/CMakeLists.txt index c9aecb9e44..d856d80dbc 100644 --- a/rosbag2_tests/CMakeLists.txt +++ b/rosbag2_tests/CMakeLists.txt @@ -121,11 +121,11 @@ if(BUILD_TESTING) ) endif() - ament_add_gmock(test_rosbag2_info_get_service_info - test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp + ament_add_gmock(test_rosbag2_cpp_get_service_info + test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) - if(TARGET test_rosbag2_info_get_service_info) - target_link_libraries(test_rosbag2_info_get_service_info + if(TARGET test_rosbag2_cpp_get_service_info) + target_link_libraries(test_rosbag2_cpp_get_service_info rosbag2_cpp::rosbag2_cpp rosbag2_storage::rosbag2_storage rosbag2_test_common::rosbag2_test_common diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp similarity index 96% rename from rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp rename to rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp index 2e268ad6d5..ee80f018c0 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_get_service_info.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp @@ -45,7 +45,8 @@ class SequentialWriterForTest : public rosbag2_cpp::writers::SequentialWriter } }; -class GetServiceInfoTest : public rosbag2_test_common::ParametrizedTemporaryDirectoryFixture +class Rosbag2CPPGetServiceInfoTest + : public rosbag2_test_common::ParametrizedTemporaryDirectoryFixture { public: void SetUp() override @@ -146,7 +147,7 @@ class GetServiceInfoTest : public rosbag2_test_common::ParametrizedTemporaryDire std::atomic_bool exit_from_node_spinner_{false}; }; -TEST_P(GetServiceInfoTest, only_topics_bag_test) { +TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_topics_only) { const std::string storage_id = GetParam(); const auto bag_path_str = get_bag_path_str(); { @@ -169,7 +170,7 @@ TEST_P(GetServiceInfoTest, only_topics_bag_test) { EXPECT_TRUE(ret_service_infos.empty()); } -TEST_P(GetServiceInfoTest, only_services_bag_test) { +TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_services_only) { const std::string storage_id = GetParam(); const std::string bag_path_str = get_bag_path_str(); @@ -236,7 +237,7 @@ TEST_P(GetServiceInfoTest, only_services_bag_test) { EXPECT_EQ(ret_service_infos[0]->serialization_format, "cdr"); } -TEST_P(GetServiceInfoTest, topics_and_services_bag_test) { +TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_topics_and_services) { const std::string storage_id = GetParam(); const std::string bag_path_str = get_bag_path_str(); @@ -331,6 +332,6 @@ TEST_P(GetServiceInfoTest, topics_and_services_bag_test) { INSTANTIATE_TEST_SUITE_P( TestInfoGetServiceInfo, - GetServiceInfoTest, + Rosbag2CPPGetServiceInfoTest, ::testing::ValuesIn(rosbag2_test_common::kTestedStorageIDs) ); From 975e07542f452e9943dcdc23f486964b77a19b69 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 01:37:08 -0800 Subject: [PATCH 6/8] Use `std::filesystem` instead of `rcpputils::fs` functions - Rationale: Deprecation of the rcpputils::fs in future See https://github.com/ros2/rcpputils/issues/164 for details Signed-off-by: Michael Orlov --- .../test_rosbag2_cpp_get_service_info.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp index ee80f018c0..9fcefb8819 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp @@ -15,6 +15,7 @@ #include #include +#include #include #include "rosbag2_cpp/info.hpp" @@ -52,17 +53,17 @@ class Rosbag2CPPGetServiceInfoTest void SetUp() override { auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = rcpputils::fs::path(temporary_dir_path_) / bag_name; + root_bag_path_ = std::filesystem::path(temporary_dir_path_) / bag_name; // Clean up potentially leftover bag files. // There may be leftovers if the system reallocates a temp directory // used by a previous test execution and the test did not have a clean exit. - rcpputils::fs::remove_all(root_bag_path_); + std::filesystem::remove_all(root_bag_path_); } void TearDown() override { - rcpputils::fs::remove_all(root_bag_path_); + std::filesystem::remove_all(root_bag_path_); } static void SetUpTestCase() @@ -116,7 +117,7 @@ class Rosbag2CPPGetServiceInfoTest std::string get_bag_path_str() const { - return root_bag_path_.string(); + return root_bag_path_.generic_string(); } bool wait_for_subscriptions( @@ -142,7 +143,7 @@ class Rosbag2CPPGetServiceInfoTest } // relative path to the root of the bag file. - rcpputils::fs::path root_bag_path_; + std::filesystem::path root_bag_path_; std::future node_spinner_future_; std::atomic_bool exit_from_node_spinner_{false}; }; From 2600f9fbcd2afbebe34ecba80b4b7811e3c6455d Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 00:23:05 -0800 Subject: [PATCH 7/8] Avoid extra metadata readout in `ros2 bag info` verb with `--verbose` Signed-off-by: Michael Orlov --- ros2bag/ros2bag/verb/info.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/ros2bag/ros2bag/verb/info.py b/ros2bag/ros2bag/verb/info.py index 5ab1000da0..d48bd06a9c 100644 --- a/ros2bag/ros2bag/verb/info.py +++ b/ros2bag/ros2bag/verb/info.py @@ -47,14 +47,14 @@ def _is_service_event_topic(self, topic_name, topic_type) -> bool: return True def main(self, *, args): # noqa: D102 - m = Info().read_metadata(args.bag_path, args.storage) - if args.topic_name: - for topic_info in m.topics_with_message_count: - if not self._is_service_event_topic(topic_info.topic_metadata.name, - topic_info.topic_metadata.type): - print(topic_info.topic_metadata.name) + if args.verbose: + Info().read_metadata_and_output_service_verbose(args.bag_path, args.storage) else: - if args.verbose: - Info().read_metadata_and_output_service_verbose(args.bag_path, args.storage) + m = Info().read_metadata(args.bag_path, args.storage) + if args.topic_name: + for topic_info in m.topics_with_message_count: + if not self._is_service_event_topic(topic_info.topic_metadata.name, + topic_info.topic_metadata.type): + print(topic_info.topic_metadata.name) else: print(m) From 28decfb7c032745934698de9b919cdfc55813719 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 7 Nov 2023 01:14:25 -0800 Subject: [PATCH 8/8] Add info_end_to_end test with `--verbose` parameter Signed-off-by: Michael Orlov --- .../bag_with_topics_and_service_events.mcap | Bin 0 -> 13271 bytes .../metadata.yaml | 57 ++++++++++++++++++ .../bag_with_topics_and_service_events.db3 | Bin 0 -> 28672 bytes .../metadata.yaml | 57 ++++++++++++++++++ .../test_rosbag2_info_end_to_end.cpp | 50 +++++++++++++++ 5 files changed, 164 insertions(+) create mode 100644 rosbag2_tests/resources/mcap/bag_with_topics_and_service_events/bag_with_topics_and_service_events.mcap create mode 100644 rosbag2_tests/resources/mcap/bag_with_topics_and_service_events/metadata.yaml create mode 100644 rosbag2_tests/resources/sqlite3/bag_with_topics_and_service_events/bag_with_topics_and_service_events.db3 create mode 100644 rosbag2_tests/resources/sqlite3/bag_with_topics_and_service_events/metadata.yaml diff --git a/rosbag2_tests/resources/mcap/bag_with_topics_and_service_events/bag_with_topics_and_service_events.mcap b/rosbag2_tests/resources/mcap/bag_with_topics_and_service_events/bag_with_topics_and_service_events.mcap new file mode 100644 index 0000000000000000000000000000000000000000..e68cdbe4b722087550459da5436a44c22b54047e GIT binary patch literal 13271 zcmeHOO^h5z74F^H#hZy8=MNHt5-Mvc2Bh`$?{v=yi$FwTN5V#4D;zLtYPzd;+Vpmh zyL)%F=I@5^1#yYQfdc{r9N-27aWLY>4T(sRKqL|pNc>4~;fUb9`swZY*_~a+>sV&` z(AD+o)$5v9uU^0U>doy>y!g>i>Zh6uXEbpwL6K*Lc?!xT?rjEiK#cRodHv+2MZs}G zaP;Vg*#*)QP%T&<(c^Ri0ei?7Fk#@g`(}4MGkOloN>6oTvxu$NlJ;!!k z$J5>BCMybjV~}m7C5kJvK^zqRPF(h3l=Vh<^`}4646@BZ4s;ldA7%L_gRU|4<_7iFHI z7T@*R$Av|``tuvVU3ulTr!N2ITW?|MNxEp&G*xeWM4I5D_AIoOtSJ4>Vxwpk`F87L zw1|Uiy8~AEAKwNelV)lH!%67Y%d&*v&EKZU7Hjr)OGfY}>p`F91aGn)B^fO(lgP48 zZQFv{wk0)AOON19*0(r;-}g9-HnJG)8V`_=siMI%ypi8)TtGrD%iNO%BLGVEeryJk zC?pps8I}%AJrwz_wezhP>Ye`$wo`J^}Hzm1ljh0%RK0`xl07DSw-+(?( z!ebUiEC)w-6Kr{qXMDjv3vFwp50;(fyIo?zVhGs)moKgha27G`#YtR3n}KcM^M>k- zhDn@q9|xlSwCKMKq^p-MuIq;H^g12S zqqe6zRBuyenqd?fW=FTE>)JsOQrFN~$1&`V+3tB}JBk9&vzbLZwBwm<`70m`FZ_CG zn(`;A)Z}#k@L!kMU;p{kqYJ11_Qf}Dxx1Q%bNdk96iZbi?I@Rg1@E%_W!X~<=fcg; zardT5dPUF2JhV|I-*|`|bn|Bg!=c=sR`4ev+Je-;Ad}R6mdi%uhFpN-TT`loTKN(Sr zSpG7wP^?qe*C<1MjgBn;h5v}*sIsn>pFQ)_1BY{W)FP(m?^jm1T2!fiD_YCjH%7-H ztmRnLB8JobrWlSY>uS+|aqw_vQcGi3{;CD--5_W$iiAk9wa(+Eq82<}0q#k`)C8Iz zvWRXar9oCNvLwmKPL?O(bE~kE84Jb~uPJ%Y9fH>)=eXQe!F%o?xwhoJE(IUR?8re} zmy)XyuV1@*>GI3|i&rkMU%N2zM}7E$X+m7Rm4*-#iQhRCf$rO`6tIu7ruN%MaZ~&4 zqr|EG_EYH8j^oN*dR@AUMKJo4V1pw5O%ub<|Mzf{G3GdqWwoug*|BKg z1|2(So3>>#7WN$1by?4|JD%-^CNFR-bp)1GB6{{tNmT*8qw|M+e0SXGIh zOnna!MydM(>{Zd^(j2166*xqj!gtT!RoU&rxZRp_yA=r3KKr%15kB5EyA>9r;1*Rr zuy%XmJ-D3UTF@SayZXH^JjRJy)x5}?)iVC-BeMA=QNo_>1$a`y_5#KTaH(kb>$0xG ztJXuJUBx$dWc`E^x5UM%J?a^;SJc!d@dvW5g4m~5gg6yNeqYv4eiz*dTry-qSoSp_ z?E}l+f~J{ZSyyj6R>!uFfX*82PRFtx54^3b>#l7(_9!}QOo3wOB@*O8k8hO&#ovN-bP?soBh((SU0r1nNP7p<2!ueNo?*C* znTBpSo}-6h5IAi&jBL9T*+$1QJ8eDk_)EqRX$0vHw55Zfz}mRGWN+gz34WHW_uQKJ zbXF1G(Pr;~wx$^&#!1#>1MvvfGzz%Qt%*!@Y04Gd&%Ws$v?j4l+{buo7>4Ay=N@SO zJ)8VJn>Bjp^EvW8!_%b0cpz>wxcA3P1VwwFuer_Kw=vN1*vvfBL8OgL+L+)189oLb zN|or6Y6FCvqswth#=~j3spA{AISyTACMYa;94eK_`5cFa!+CMIa2Ijtc|Hwh0*U0A zc|Ohmu7}1SxI@FNhUekwaBxfQi0ymO=`6X{XC&H65`u|uB#TIi1jvVj2U?OHT0kw0 zi#`hpWYCcyfn>o@oq>rO&&O--BP(S)Bl3cr(GtX!8G)1)$Ti$z0M-Oq9)fF9lCuFz z;cN>>(wrmU?`)#btnpAafAf>KD(iL(ZRFd8k)1iv4u|a>oai<4{He^nc}CNNk-1l; zsLfL`ACL*XBafq(AsWC#s0oKN^P}QpKPq-+JUn^$RT?Q-vFa#I^41wni zfg6d$)a=FBfo`f~-_^H?fkNnj9yz`x>8<3%d6j5dK0y%ptV&Ls-a7b zDs*Mz+Fbp`k}2Czo^;#wjmdUs^}6uP?uLWqlKU zb7^zlwQ9NoMl~u|*UD)1TPrK`%|XLa2*iiu+yu@4hq&w9#P4DE;}R*|eDFLyk+ac1#yk(!9?@$$Pq6 zZ7^VdEts%?ylSZMc^*0*-6%a(LW^VfQg*e3G;BCzCNew6 zc+3)7Uw&mHosn}y%Sl=xlg{IuqG^(r!vzQ)K~geOCQ~3p$fPqlDVJ7NMakt0s+P?b zwQQy+3dMX{le|IN;w%lq97-VAaY@Rw38zcp5K6e}GLwgF=BLn;H_gdoPvmQ2`0PPtz zH2XLfFFnGA=Kmw3A9IsG82{tB+2lT)vW+3Y5MT%}1Q-Ggflm(tM_(FAa^mKTcbDta z9VqMmSZW}mqf|4jC_<(gPFsm)S{LP+J>7s9g!5x8vnOjKnL*azm0Hsgqbe)n=JDQJop00M% zl}(oyOUEzs!LF{;PS*=VN$#aW(l))IG`m!cJoD4uEOs+?HC54Z$FWxA(sl^H7lIJZ$0f{2TG>yREdhr3<5KnmY~N{H@)@{T9)_DzjUo~mT>5giawrG^a7VMK2q(E<_G5`|`8U;#)P z$QBkBc!onW_)bYS{J0bw;|kO7emNR^5q=?vyiPOGK}P@bAMY4$ z2F<)e48uZumTjnCm)@ zyis0XUcD|~TU*^IU+(DCS1te;Rfa6Q{~0kLPh zZh-b|cpTi|&UqI3KhJ-SOC3%=n!G#7PrN%ZHvW_G^XKM3$To%mLx3T`5MT%}1Q-Gg z0fs;;0`)CE!6g$%U!8jI)v@3G?X3s&SE0inhNkb9qB#t0+K>e)MT;!R99m>O^!{&S z)vL(_7Xwd+sH-1;@(4Y*uI`UfPwThho~LiT^&RSI9A@SIzm~~AxW}XRS-;dbGG z{^>BseV$f%XY@$7a8mqIe|xXZ{-{6lus`zojp)d0{G+y!lV>;bVZs~P@O^&$*Y`sw zsLziN+DC5n`APh3$LVmyH^6s&?ZTy~0pHgDbE4~KVZi=y1p9{{EkBN8U;XL#I~ouj zIC|dSoClGzANNQ0uz&dA@t>k2-(SaVBm3A#M~j{hH1gq41oVdw?x|7GfBBbNZ6o{f z7LFDk`yDaVi?%zA`3Cr|fB3;Kq6S>}dpqc@u17lxJMZThZO20cK6S{Y{+aq~>d&d) zrhb+BF!l4)&r0RC;PSvbEj+9&`^m1q=zF&YUAl)V{l6o62PHw*XFp>y#>k`DS1_=f)im$~C- literal 0 HcmV?d00001 diff --git a/rosbag2_tests/resources/sqlite3/bag_with_topics_and_service_events/metadata.yaml b/rosbag2_tests/resources/sqlite3/bag_with_topics_and_service_events/metadata.yaml new file mode 100644 index 0000000000..d0e796c5b1 --- /dev/null +++ b/rosbag2_tests/resources/sqlite3/bag_with_topics_and_service_events/metadata.yaml @@ -0,0 +1,57 @@ +rosbag2_bagfile_information: + version: 8 + storage_identifier: sqlite3 + duration: + nanoseconds: 70633730 + starting_time: + nanoseconds_since_epoch: 1699345836023194036 + message_count: 10 + topics_with_message_count: + - topic_metadata: + name: /events/write_split + type: rosbag2_interfaces/msg/WriteSplitEvent + serialization_format: cdr + offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false" + type_description_hash: RIHS01_5ef58f7106a5cff8f5a794028c18117ee21015850ddcc567df449f41932960f8 + message_count: 0 + - topic_metadata: + name: /test_service1/_service_event + type: test_msgs/srv/BasicTypes_Event + serialization_format: cdr + offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 1\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false" + type_description_hash: RIHS01_5b9988a4805a06ae22dff12903a774ccda710e9514926b826ffc884e3a9a982e + message_count: 4 + - topic_metadata: + name: /test_service2/_service_event + type: test_msgs/srv/BasicTypes_Event + serialization_format: cdr + offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 1\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false" + type_description_hash: RIHS01_5b9988a4805a06ae22dff12903a774ccda710e9514926b826ffc884e3a9a982e + message_count: 4 + - topic_metadata: + name: /test_topic1 + type: test_msgs/msg/Strings + serialization_format: cdr + offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false" + type_description_hash: RIHS01_eee55533636293ac7c94c62432eedb5777eb849847d2a17b4dcead8c4a20ab32 + message_count: 1 + - topic_metadata: + name: /test_topic2 + type: test_msgs/msg/Strings + serialization_format: cdr + offered_qos_profiles: "- history: 3\n depth: 0\n reliability: 1\n durability: 2\n deadline:\n sec: 9223372036\n nsec: 854775807\n lifespan:\n sec: 9223372036\n nsec: 854775807\n liveliness: 1\n liveliness_lease_duration:\n sec: 9223372036\n nsec: 854775807\n avoid_ros_namespace_conventions: false" + type_description_hash: RIHS01_eee55533636293ac7c94c62432eedb5777eb849847d2a17b4dcead8c4a20ab32 + message_count: 1 + compression_format: "" + compression_mode: "" + relative_file_paths: + - bag_with_topics_and_service_events.db3 + files: + - path: bag_with_topics_and_service_events.db3 + starting_time: + nanoseconds_since_epoch: 1699345836023194036 + duration: + nanoseconds: 70633730 + message_count: 10 + custom_data: ~ + ros_distro: "" \ No newline at end of file diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp index de1787e389..ae4f9a7c37 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp @@ -68,6 +68,56 @@ TEST_P(InfoEndToEndTestFixture, info_end_to_end_test) { "Serialization Format: cdr")); } +TEST_P(InfoEndToEndTestFixture, info_with_verbose_option_end_to_end_test) { + internal::CaptureStdout(); + auto exit_code = execute_and_wait_until_completion( + "ros2 bag info bag_with_topics_and_service_events --verbose", + bags_path_); + std::string output = internal::GetCapturedStdout(); + auto expected_storage = GetParam(); + auto expected_file = rosbag2_test_common::bag_filename_for_storage_id( + "bag_with_topics_and_service_events", GetParam()); + std::string expected_ros_distro = "unknown"; + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); + // The bag size depends on the os and is not asserted, the time is asserted time zone independent + EXPECT_THAT( + output, ContainsRegex( + "\nFiles: " + expected_file + + "\nBag size: .*B" + "\nStorage id: " + expected_storage + + "\nROS Distro: " + expected_ros_distro + + "\nDuration: 0\\.70s" + "\nStart: Nov 7 2023 00:30:36\\..* \\(1699345836\\..*\\)" + "\nEnd: Nov 7 2023 00:30:36\\..* \\(1699345836\\..*\\)" + "\nMessages: 2" + "\nTopic information: ")); + EXPECT_THAT( + output, HasSubstr( + "Topic: /events/write_split | Type: rosbag2_interfaces/msg/WriteSplitEvent | Count: 0 | " + "Serialization Format: cdr\n")); + EXPECT_THAT( + output, HasSubstr( + "Topic: /test_topic1 | Type: test_msgs/msg/Strings | Count: 1 | " + "Serialization Format: cdr\n")); + EXPECT_THAT( + output, HasSubstr( + "Topic: /test_topic2 | Type: test_msgs/msg/Strings | Count: 1 | " + "Serialization Format: cdr\n")); + + EXPECT_THAT(output, HasSubstr("Service: 2\n")); + + EXPECT_THAT( + output, HasSubstr( + "Service: /test_service1 | Type: test_msgs/srv/BasicTypes | Request Count: 2 | " + "Response Count: 2 | Serialization Format: cdr\n")); + + EXPECT_THAT( + output, HasSubstr( + "Service: /test_service2 | Type: test_msgs/srv/BasicTypes | Request Count: 2 | " + "Response Count: 2 | Serialization Format: cdr\n")); +} + // TODO(Martin-Idel-SI): Revisit exit code non-zero here, gracefully should be exit code zero TEST_P(InfoEndToEndTestFixture, info_fails_gracefully_if_bag_does_not_exist) { internal::CaptureStderr();