From ece2da46a1d21e569a1fac3fe6bbcdb424a99c6c Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Wed, 26 Oct 2022 15:11:39 -0700 Subject: [PATCH] [humble] Redesign record_services tests to make them more deterministic (#1122) Signed-off-by: Michael Orlov Signed-off-by: Michael Orlov (cherry picked from commit 5f0c7d41668ef5c1269d12d0bfa786cd5263f015) --- .../mock_sequential_writer.hpp | 24 +++++++++++----- .../test/rosbag2_transport/test_record.cpp | 6 ++-- .../test_record_services.cpp | 28 ++++++++----------- 3 files changed, 33 insertions(+), 25 deletions(-) diff --git a/rosbag2_transport/test/rosbag2_transport/mock_sequential_writer.hpp b/rosbag2_transport/test/rosbag2_transport/mock_sequential_writer.hpp index d5bfb30a86..bdedd97b4d 100644 --- a/rosbag2_transport/test/rosbag2_transport/mock_sequential_writer.hpp +++ b/rosbag2_transport/test/rosbag2_transport/mock_sequential_writer.hpp @@ -57,12 +57,7 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn messages_per_topic_[message->topic_name] += 1; messages_per_file_ += 1; if (messages_per_file_ == max_messages_per_file_) { // "Split" the bag every few messages - auto info = std::make_shared(); - info->closed_file = "BagFile" + std::to_string(file_number_); - file_number_ += 1; - info->opened_file = "BagFile" + std::to_string(file_number_); - callback_manager_.execute_callbacks(rosbag2_cpp::bag_events::BagEvent::WRITE_SPLIT, info); - messages_per_file_ = 0; + this->split_bagfile(); } } @@ -73,6 +68,16 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn return true; } + void split_bagfile() + { + auto info = std::make_shared(); + info->closed_file = "BagFile" + std::to_string(file_number_); + file_number_ += 1; + info->opened_file = "BagFile" + std::to_string(file_number_); + callback_manager_.execute_callbacks(rosbag2_cpp::bag_events::BagEvent::WRITE_SPLIT, info); + messages_per_file_ = 0; + } + void add_event_callbacks(const rosbag2_cpp::bag_events::WriterEventCallbacks & callbacks) override { @@ -103,6 +108,11 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn return topics_; } + void set_max_messages_per_file(size_t max_messages_per_file) + { + max_messages_per_file_ = max_messages_per_file; + } + size_t max_messages_per_file() const { return max_messages_per_file_; @@ -117,7 +127,7 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn bool snapshot_mode_ = false; rosbag2_cpp::bag_events::EventCallbackManager callback_manager_; size_t file_number_ = 0; - const size_t max_messages_per_file_ = 5; + size_t max_messages_per_file_ = 0; }; #endif // ROSBAG2_TRANSPORT__MOCK_SEQUENTIAL_WRITER_HPP_ diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index ece991a127..71456d30d1 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -324,6 +324,9 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called) }; writer_->add_event_callbacks(callbacks); + auto & mock_writer = dynamic_cast(writer_->get_implementation_handle()); + mock_writer.set_max_messages_per_file(5); + rosbag2_transport::RecordOptions record_options = {false, false, {string_topic}, "rmw_format", 100ms}; auto recorder = std::make_shared( @@ -333,8 +336,7 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called) start_async_spin(recorder); auto & writer = recorder->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + mock_writer = dynamic_cast(writer.get_implementation_handle()); const size_t expected_messages = mock_writer.max_messages_per_file() + 1; diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp index 7baa6ee4dc..6f47748480 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_services.cpp @@ -25,11 +25,7 @@ #include "rosbag2_transport/recorder.hpp" #include "rosbag2_test_common/publication_manager.hpp" -#include "rosbag2_test_common/wait_for.hpp" -#include "test_msgs/msg/arrays.hpp" -#include "test_msgs/msg/basic_types.hpp" -#include "test_msgs/msg/strings.hpp" #include "test_msgs/message_fixtures.hpp" #include "record_integration_fixture.hpp" @@ -56,10 +52,6 @@ class RecordSrvsTest : public RecordIntegrationTestFixture { } - void subscription_callback(const test_msgs::msg::Strings::SharedPtr) - { - } - /// Use SetUp instead of ctor because we want to ASSERT some preconditions for the tests void SetUp() override { @@ -76,7 +68,7 @@ class RecordSrvsTest : public RecordIntegrationTestFixture auto string_message = get_messages_strings()[1]; rosbag2_test_common::PublicationManager pub_manager; - pub_manager.setup_publisher(test_topic_, string_message, 50); + pub_manager.setup_publisher(test_topic_, string_message, 10); const std::string ns = "/" + recorder_name_; cli_snapshot_ = client_node_->create_client(ns + "/snapshot"); @@ -124,7 +116,7 @@ class RecordSrvsTest : public RecordIntegrationTestFixture // Basic configuration const std::string recorder_name_ = "rosbag2_recorder_for_test_srvs"; const std::chrono::seconds service_wait_timeout_ {2}; - const std::chrono::seconds service_call_timeout_ {1}; + const std::chrono::seconds service_call_timeout_ {2}; const std::string test_topic_ = "/recorder_srvs_test_topic"; // Orchestration @@ -140,14 +132,18 @@ class RecordSrvsTest : public RecordIntegrationTestFixture TEST_F(RecordSrvsTest, trigger_snapshot) { auto & writer = recorder_->get_writer_handle(); - MockSequentialWriter & mock_writer = - static_cast(writer.get_implementation_handle()); + auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); EXPECT_THAT(mock_writer.get_messages().size(), Eq(0u)); - // Sleep for 2 seconds to allow messages to accumulate in snapshot buffer - std::chrono::duration duration(2.0); - std::this_thread::sleep_for(duration); - EXPECT_THAT(mock_writer.get_snapshot_buffer().size(), Gt(0u)); + // Wait for messages to be appeared in snapshot_buffer + std::chrono::duration timeout = std::chrono::seconds(10); + using clock = std::chrono::steady_clock; + auto start = clock::now(); + while (mock_writer.get_snapshot_buffer().empty()) { + std::this_thread::sleep_for(std::chrono::milliseconds(30)); + EXPECT_LE((clock::now() - start), timeout) << "Failed to capture messages in time"; + } + EXPECT_THAT(mock_writer.get_messages().size(), Eq(0u)); successful_service_request(cli_snapshot_); EXPECT_THAT(mock_writer.get_messages().size(), Ne(0u));