From 604cebcf11775151efa94f7c30ba1aea68e90c5c Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 23 Aug 2024 14:53:59 -0400 Subject: [PATCH] Small cleanups to the rosbag2 tests. (#1792) * Small cleanups to the rosbag2 tests. 1. Rename "wait_for_srvice_to_be_ready" to "wait_for_service_to_be_ready". 2. Make some of the constants constexpr, so we no longer have to capture them. Signed-off-by: Chris Lalancette --- .../rosbag2_test_common/client_manager.hpp | 2 +- .../test_rosbag2_cpp_get_service_info.cpp | 6 ++-- .../test/rosbag2_transport/test_record.cpp | 11 +++---- .../rosbag2_transport/test_record_all.cpp | 12 ++++---- .../test_record_all_ignore_leaf_topics.cpp | 2 +- .../test_record_all_no_discovery.cpp | 4 +-- .../test_record_all_use_sim_time.cpp | 2 +- .../rosbag2_transport/test_record_regex.cpp | 30 +++++++++---------- 8 files changed, 35 insertions(+), 34 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 a11502a70..ac081692d 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp @@ -92,7 +92,7 @@ class ClientManager : public rclcpp::Node return true; } - bool wait_for_srvice_to_be_ready(std::chrono::duration timeout = std::chrono::seconds(5)) + bool wait_for_service_to_be_ready(std::chrono::duration timeout = std::chrono::seconds(5)) { using clock = std::chrono::system_clock; auto start = clock::now(); 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 c316eb404..3ab7aeb98 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 @@ -198,7 +198,7 @@ TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_services_only auto cleanup_process_handle = rcpputils::make_scope_exit( [&]() {stop_spinning();}); - ASSERT_TRUE(service_client_manager->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_client_manager->wait_for_service_to_be_ready()); ASSERT_TRUE(wait_for_subscriptions(*recorder, {"/test_service/_service_event"})); constexpr size_t num_service_requests = 3; @@ -252,8 +252,8 @@ TEST_P(Rosbag2CPPGetServiceInfoTest, get_service_info_for_bag_with_topics_and_se std::make_shared>( "test_service2"); - ASSERT_TRUE(service_client_manager1->wait_for_srvice_to_be_ready()); - ASSERT_TRUE(service_client_manager2->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(service_client_manager1->wait_for_service_to_be_ready()); + ASSERT_TRUE(service_client_manager2->wait_for_service_to_be_ready()); rosbag2_test_common::PublicationManager pub_manager; auto message = get_messages_strings()[0]; diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 1cb9a0883..b602af80f 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -63,7 +63,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 4; + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -144,7 +144,8 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop) ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str())); pub_manager.run_publishers(); - size_t expected_messages = 4; // 4 because was running recorder-record() and publishers twice + // 4 because we're running recorder->record() and publishers twice + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -195,7 +196,7 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 2; + constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -259,7 +260,7 @@ TEST_F(RecordIntegrationTestFixture, records_sensor_data) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 2; + constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -431,7 +432,7 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called) auto & writer = recorder->get_writer_handle(); mock_writer = dynamic_cast(writer.get_implementation_handle()); - const size_t expected_messages = mock_writer.max_messages_per_file() + 1; + size_t expected_messages = mock_writer.max_messages_per_file() + 1; rosbag2_test_common::PublicationManager pub_manager; pub_manager.setup_publisher(string_topic, string_message, expected_messages); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index c6121bf8f..d79f960ce 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -65,7 +65,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); - size_t expected_messages = 4; + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -104,8 +104,8 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a start_async_spin(recorder); - ASSERT_TRUE(client_manager_1->wait_for_srvice_to_be_ready()); - ASSERT_TRUE(client_manager_2->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready()); + ASSERT_TRUE(client_manager_2->wait_for_service_to_be_ready()); // By default, only client introspection is enabled. // For one request, service event topic get 2 messages. @@ -115,7 +115,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); - size_t expected_messages = 4; + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -148,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->wait_for_srvice_to_be_ready()); + ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready()); pub_manager.run_publishers(); @@ -159,7 +159,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); - size_t expected_messages = 3; + constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp index 8fa487b4d..b33eaaba2 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_ignore_leaf_topics.cpp @@ -68,7 +68,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_two_topics_ignore_l MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 2; + constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp index 92ac9c1fd..594effcbf 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_no_discovery.cpp @@ -53,13 +53,13 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_ MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 0; + constexpr size_t expected_messages = 0; rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(2), [&mock_writer, &expected_messages]() { return mock_writer.get_messages().size() > expected_messages; }); - (void) expected_messages; // we can't say anything here, there might be some rosout + // We can't EXPECT anything here, since there may be some messages from rosout auto recorded_topics = mock_writer.get_topics(); EXPECT_EQ(0u, recorded_topics.count(topic)); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp index 7c0476f58..04b31db19 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all_use_sim_time.cpp @@ -112,7 +112,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_with_sim_time) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 10; + constexpr size_t expected_messages = 10; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &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 15770b257..3c36289dc 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp @@ -86,7 +86,7 @@ TEST_F(RecordIntegrationTestFixture, regex_topics_recording) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 3; + constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -161,7 +161,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_topic_recording) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 3; + constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -236,7 +236,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_topic_topic_recording) MockSequentialWriter & mock_writer = static_cast(writer.get_implementation_handle()); - size_t expected_messages = 3; + constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -296,11 +296,11 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) start_async_spin(recorder); - 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()); + 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()); auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); @@ -311,7 +311,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) ASSERT_TRUE(service_manager_b1->send_request()); ASSERT_TRUE(service_manager_b2->send_request()); - size_t expected_messages = 4; + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() { @@ -369,11 +369,11 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording start_async_spin(recorder); - 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()); + 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()); auto & writer = recorder->get_writer_handle(); auto & mock_writer = dynamic_cast(writer.get_implementation_handle()); @@ -384,7 +384,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording ASSERT_TRUE(service_manager_b1->send_request()); ASSERT_TRUE(service_manager_b2->send_request()); - size_t expected_messages = 4; + constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), [&mock_writer, &expected_messages]() {