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

Removed warnings #1794

Merged
merged 3 commits into from
Aug 28, 2024
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
8 changes: 4 additions & 4 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand Down Expand Up @@ -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";
Expand Down Expand Up @@ -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";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
10 changes: 5 additions & 5 deletions rosbag2_transport/test/rosbag2_transport/test_record_regex.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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";
Expand Down Expand Up @@ -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";
Expand Down
Loading