diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index b602af80f..dd5288eb5 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -66,7 +66,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -148,7 +148,7 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop) constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -199,7 +199,7 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata) constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -263,7 +263,7 @@ TEST_F(RecordIntegrationTestFixture, records_sensor_data) constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp index d79f960ce..597deb40a 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_all.cpp @@ -68,7 +68,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); EXPECT_TRUE(ret) << "failed to capture expected messages in time"; @@ -118,7 +118,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); EXPECT_TRUE(ret) << "failed to capture expected messages in time"; @@ -162,7 +162,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); EXPECT_TRUE(ret) << "failed to capture expected messages in time"; 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 b33eaaba2..955855d13 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 @@ -71,7 +71,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_two_topics_ignore_l constexpr size_t expected_messages = 2; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_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 594effcbf..5e30702e6 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 @@ -56,7 +56,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_ constexpr size_t expected_messages = 0; rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(2), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() > expected_messages; }); // We can't EXPECT anything here, since there may be some messages from rosout 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 04b31db19..4b6476ac3 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 @@ -115,7 +115,7 @@ TEST_F(RecordIntegrationTestFixture, record_all_with_sim_time) constexpr size_t expected_messages = 10; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp index 3c36289dc..f6d4d81fc 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp @@ -89,7 +89,7 @@ TEST_F(RecordIntegrationTestFixture, regex_topics_recording) constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -164,7 +164,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_topic_recording) constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -239,7 +239,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_topic_topic_recording) constexpr size_t expected_messages = 3; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); auto recorded_messages = mock_writer.get_messages(); @@ -314,7 +314,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_regex_service_recording) constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); EXPECT_TRUE(ret) << "failed to capture expected messages in time"; @@ -387,7 +387,7 @@ TEST_F(RecordIntegrationTestFixture, regex_and_exclude_service_service_recording constexpr size_t expected_messages = 4; auto ret = rosbag2_test_common::wait_until_shutdown( std::chrono::seconds(5), - [&mock_writer, &expected_messages]() { + [ =, &mock_writer]() { return mock_writer.get_messages().size() >= expected_messages; }); EXPECT_TRUE(ret) << "failed to capture expected messages in time";