Skip to content

Commit

Permalink
Switch to using MockRecorder.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Sep 4, 2024
1 parent c73fa80 commit 11bb864
Show file tree
Hide file tree
Showing 4 changed files with 46 additions and 121 deletions.
62 changes: 24 additions & 38 deletions rosbag2_transport/test/rosbag2_transport/test_record_all.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#include "rosbag2_transport/recorder.hpp"

#include "mock_recorder.hpp"
#include "record_integration_fixture.hpp"

using namespace std::chrono_literals; // NOLINT
Expand All @@ -51,27 +52,20 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are

rosbag2_transport::RecordOptions record_options =
{true, false, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms};
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /string_topic
// /events/write_split
// /array_topic
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 3;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(pub_manager.wait_for_matched(array_topic.c_str()));
ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));

// At this point, we expect that the topics /string_topic, /array_topic, and /events/write_split
// are available to be recorded. However, wait_for_matched() only checks for /string_topic
// and /array_topic, so ask the recorder to make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/events/write_split"));

pub_manager.run_publishers();

auto & writer = recorder->get_writer_handle();
Expand Down Expand Up @@ -110,26 +104,22 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a

rosbag2_transport::RecordOptions record_options =
{false, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms};
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /test_service_1/_service_event
// /test_service_2/_service_event
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 2;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready());
ASSERT_TRUE(client_manager_2->wait_for_service_to_be_ready());

// At this point, we expect that the services /test_service_1 and /test_service_2, along with
// the event topics /test_service_1/_service_event and /test_service_2/_service_event are
// available to be recorded. However, wait_for_service_to_be_ready() only checks the services,
// not the event topics, so ask the recorder to make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service_1/_service_event"));
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service_2/_service_event"));

// By default, only client introspection is enabled.
// For one request, service event topic gets 2 messages.
ASSERT_TRUE(client_manager_1->send_request());
Expand Down Expand Up @@ -163,28 +153,24 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a

rosbag2_transport::RecordOptions record_options =
{true, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms};
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /test_service/_service_event
// /string_topic
// /events/write_split
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 3;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));

ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready());

// At this point, we expect that the service /test_service_1, along with the topic /string_topic,
// along with the event topic /test_service_1, along with the split topic /events/write_split are
// available to be recorded. However, wait_for_matched() and wait_for_service_to_be_ready() only
// check on the service and the topic, not the event or the split topic, so ask the recorder to
// make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service/_service_event"));
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/events/write_split"));

pub_manager.run_publishers();

// By default, only client introspection is enabled.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,18 +42,6 @@ TEST_F(RecordIntegrationTestFixture, record_all_include_unpublished_false_ignore
recorder->record();
start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /rosout
// /parameter_events
// /events/write_split
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 3;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered(string_topic));
ASSERT_FALSE(recorder->topic_available_for_recording(string_topic));
}
Expand All @@ -72,19 +60,6 @@ TEST_F(RecordIntegrationTestFixture, record_all_include_unpublished_true_include
recorder->record();
start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /string_topic
// /rosout
// /parameter_events
// /events/write_split
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 4;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered(string_topic));
ASSERT_TRUE(recorder->topic_available_for_recording(string_topic));
}
Expand All @@ -105,18 +80,6 @@ TEST_F(
recorder->record();
start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /rosout
// /parameter_events
// /events/write_split
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 3;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered(string_topic));
ASSERT_FALSE(recorder->topic_available_for_recording(string_topic));

Expand All @@ -128,18 +91,6 @@ TEST_F(
// Publish 10 messages at a 30ms interval for a steady 300 milliseconds worth of data
pub_manager.setup_publisher(
string_topic, string_message, 10, rclcpp::QoS{rclcpp::KeepAll()}, 30ms);
// Wait again until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /string_topic
// /rosout
// /parameter_events
// /events/write_split
discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 4;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));
pub_manager.run_publishers();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,23 +100,15 @@ TEST_F(RecordIntegrationTestFixture, record_all_with_sim_time)

start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /clock
// /string_topic
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 2;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));

ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered(string_topic));

ASSERT_TRUE(recorder->topic_available_for_recording(string_topic));

// We have to ensure that the /clock topic is available as well
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/clock"));

pub_manager.run_publishers();

auto & writer = recorder->get_writer_handle();
Expand Down
42 changes: 19 additions & 23 deletions rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
#include "test_msgs/message_fixtures.hpp"
#include "test_msgs/srv/basic_types.hpp"

#include "mock_recorder.hpp"
#include "record_integration_fixture.hpp"

using namespace std::chrono_literals; // NOLINT
Expand Down Expand Up @@ -289,29 +290,26 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording)
auto service_manager_b2 =
std::make_shared<rosbag2_test_common::ClientManager<test_msgs::srv::BasicTypes>>(b2);

auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

start_async_spin(recorder);

// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /still_nice_servce/_service_event
// /awesome_nice_service/_service_event
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 2;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

ASSERT_TRUE(service_manager_v1->wait_for_service_to_be_ready());
ASSERT_TRUE(service_manager_v2->wait_for_service_to_be_ready());
ASSERT_TRUE(service_manager_e1->wait_for_service_to_be_ready());
ASSERT_TRUE(service_manager_b1->wait_for_service_to_be_ready());
ASSERT_TRUE(service_manager_b2->wait_for_service_to_be_ready());

// At this point, we expect that the services /still_nice_service and /awesome_nice_service,
// along with the event topics /still_nice_service/_service_event
// and /awesome_nice_service/_service_event are available to be recorded. However,
// wait_for_service_to_be_ready() only checks the services, not the event topics, so ask the
// recorder to make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/still_nice_service/_service_event"));
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/awesome_nice_service/_service_event"));

auto & writer = recorder->get_writer_handle();
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

Expand Down Expand Up @@ -373,19 +371,9 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording
auto service_manager_b2 =
std::make_shared<rosbag2_test_common::ClientManager<test_msgs::srv::BasicTypes>>(b2);

auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();
// Wait until recorder discovery is complete, otherwise messages might be missed.
// The currently expected topics:
// /still_nice_servce/_service_event
// /awesome_nice_service/_service_event
auto discovery_ret = rosbag2_test_common::wait_until_condition(
[&recorder]() {
return recorder->subscriptions().size() == 2;
},
std::chrono::seconds(5));
ASSERT_TRUE(discovery_ret);

start_async_spin(recorder);

Expand All @@ -395,6 +383,14 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording
ASSERT_TRUE(service_manager_b1->wait_for_service_to_be_ready());
ASSERT_TRUE(service_manager_b2->wait_for_service_to_be_ready());

// At this point, we expect that the services /still_nice_service and /awesome_nice_service,
// along with the event topics /still_nice_service/_service_event
// and /awesome_nice_service/_service_event are available to be recorded. However,
// wait_for_service_to_be_ready() only checks the services, not the event topics, so ask the
// recorder to make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/still_nice_service/_service_event"));
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/awesome_nice_service/_service_event"));

auto & writer = recorder->get_writer_handle();
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

Expand Down

0 comments on commit 11bb864

Please sign in to comment.