Skip to content

Commit

Permalink
Removed warnings (#1794) (#1810)
Browse files Browse the repository at this point in the history
* Removed warnings

* compile with windows

* make linters happy

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
(cherry picked from commit 88c51a1)

Co-authored-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
mergify[bot] and ahcorde authored Sep 18, 2024
1 parent 4769ed3 commit 5bfef44
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 15 deletions.
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
6 changes: 3 additions & 3 deletions rosbag2_transport/test/rosbag2_transport/test_record_all.cpp
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

0 comments on commit 5bfef44

Please sign in to comment.