Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Redesign record_services tests to make them more deterministic #1122

Merged
merged 1 commit into from
Oct 26, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions rosbag2_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -231,8 +231,6 @@ function(create_tests_for_rmw_implementation)
LINK_LIBS rosbag2_transport
AMENT_DEPS test_msgs rosbag2_test_common)

ament_add_test_label(test_record_services${target_suffix} xfail)

if(${rmw_implementation} MATCHES "rmw_cyclonedds(.*)")
ament_add_test_label(test_play_services__rmw_cyclonedds_cpp xfail)
endif()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_cpp::bag_events::BagSplitInfo>();
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();
}
}

Expand All @@ -81,12 +76,6 @@ class MockSequentialWriter : public rosbag2_cpp::writer_interfaces::BaseWriterIn
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;
split_bagfile_called_ = true;
}

bool split_bagfile_called()
{
return split_bagfile_called_;
}

void
Expand Down Expand Up @@ -120,6 +109,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_;
Expand All @@ -134,8 +128,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;
bool split_bagfile_called_ = false;
size_t max_messages_per_file_ = 0;
};

#endif // ROSBAG2_TRANSPORT__MOCK_SEQUENTIAL_WRITER_HPP_
6 changes: 4 additions & 2 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -324,6 +324,9 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called)
};
writer_->add_event_callbacks(callbacks);

auto & mock_writer = dynamic_cast<MockSequentialWriter &>(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<rosbag2_transport::Recorder>(
Expand All @@ -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<MockSequentialWriter &>(writer.get_implementation_handle());
mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

const size_t expected_messages = mock_writer.max_messages_per_file() + 1;

Expand Down
70 changes: 41 additions & 29 deletions rosbag2_transport/test/rosbag2_transport/test_record_services.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,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"
Expand All @@ -43,7 +39,7 @@ class RecordSrvsTest : public RecordIntegrationTestFixture
using Snapshot = rosbag2_interfaces::srv::Snapshot;
using SplitBagfile = rosbag2_interfaces::srv::SplitBagfile;

explicit RecordSrvsTest(const bool snapshot_mode)
explicit RecordSrvsTest(bool snapshot_mode = false)
: RecordIntegrationTestFixture(),
snapshot_mode_(snapshot_mode)
{}
Expand All @@ -59,10 +55,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
{
Expand All @@ -79,7 +71,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<Snapshot>(ns + "/snapshot");
Expand Down Expand Up @@ -131,7 +123,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
Expand All @@ -157,32 +149,52 @@ class RecordSrvsSnapshotTest : public RecordSrvsTest
TEST_F(RecordSrvsSnapshotTest, trigger_snapshot)
{
auto & writer = recorder_->get_writer_handle();
MockSequentialWriter & mock_writer =
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(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<float> 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<int> 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<Snapshot>(cli_snapshot_);
EXPECT_THAT(mock_writer.get_messages().size(), Ne(0u));
}

class RecordSrvsSplitBagfileTest : public RecordSrvsTest
{
protected:
RecordSrvsSplitBagfileTest()
: RecordSrvsTest(false /*snapshot_mode*/) {}
};

TEST_F(RecordSrvsSplitBagfileTest, split_bagfile)
TEST_F(RecordSrvsTest, split_bagfile)
{
auto & writer = recorder_->get_writer_handle();
MockSequentialWriter & mock_writer =
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());
EXPECT_FALSE(mock_writer.split_bagfile_called());
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());
bool callback_called = false;
std::string closed_file, opened_file;
rosbag2_cpp::bag_events::WriterEventCallbacks callbacks;
callbacks.write_split_callback =
[&callback_called, &closed_file, &opened_file](rosbag2_cpp::bag_events::BagSplitInfo & info) {
closed_file = info.closed_file;
opened_file = info.opened_file;
callback_called = true;
};
mock_writer.add_event_callbacks(callbacks);

// Wait for messages to be appeared in writer buffer
std::chrono::duration<int> timeout = std::chrono::seconds(10);
using clock = std::chrono::steady_clock;
auto start = clock::now();
while (mock_writer.get_messages().empty()) {
std::this_thread::sleep_for(std::chrono::milliseconds(30));
EXPECT_LE((clock::now() - start), timeout) << "Failed to capture messages in time";
}

ASSERT_FALSE(callback_called);
successful_service_request<SplitBagfile>(cli_split_bagfile_);
EXPECT_TRUE(mock_writer.split_bagfile_called());

// Confirm that the callback was called and the file names have been sent with the event
ASSERT_TRUE(callback_called);
EXPECT_EQ(closed_file, "BagFile0");
EXPECT_EQ(opened_file, "BagFile1");
}