Skip to content

Commit

Permalink
chore: style and warning fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Janosch Machowinski <[email protected]>
  • Loading branch information
Janosch Machowinski authored and Janosch Machowinski committed Jan 10, 2025
1 parent ba78768 commit 27b2d0e
Showing 1 changed file with 4 additions and 28 deletions.
32 changes: 4 additions & 28 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -918,9 +918,6 @@ TYPED_TEST(TestExecutors, dropSomeTimer)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

// delete timer 2. Note, the executor uses an unordered map internally, to order
Expand All @@ -938,9 +935,6 @@ TYPED_TEST(TestExecutors, dropSomeTimer)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

ASSERT_TRUE(timer1_works || timer2_works);
Expand Down Expand Up @@ -975,9 +969,6 @@ TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

// delete node 1.
Expand All @@ -991,9 +982,6 @@ TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

ASSERT_TRUE(timer2_works);
Expand All @@ -1010,11 +998,11 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)
bool sub2_works = false;

auto sub1 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub1_works](const test_msgs::msg::Empty & msg) {
[&sub1_works](const test_msgs::msg::Empty &) {
sub1_works = true;
});
auto sub2 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub2_works](const test_msgs::msg::Empty & msg) {
[&sub2_works](const test_msgs::msg::Empty &) {
sub2_works = true;
});

Expand All @@ -1032,9 +1020,6 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

// delete subscription 2. Note, the executor uses an unordered map internally, to order
Expand All @@ -1054,9 +1039,6 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

ASSERT_TRUE(sub1_works || sub2_works);
Expand All @@ -1075,11 +1057,11 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
bool sub2_works = false;

auto sub1 = node1->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub1_works](const test_msgs::msg::Empty & msg) {
[&sub1_works](const test_msgs::msg::Empty &) {
sub1_works = true;
});
auto sub2 = node2->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
[&sub2_works](const test_msgs::msg::Empty & msg) {
[&sub2_works](const test_msgs::msg::Empty &) {
sub2_works = true;
});

Expand All @@ -1099,9 +1081,6 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

// delete node 2.
Expand All @@ -1117,9 +1096,6 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)

const auto cur_time = std::chrono::steady_clock::now();
ASSERT_LT(cur_time, max_end_time);
if(cur_time > max_end_time) {
return;
}
}

ASSERT_TRUE(sub1_works);
Expand Down

0 comments on commit 27b2d0e

Please sign in to comment.