Skip to content

Commit 8f8aab8

Browse files
Janosch MachowinskiJanosch Machowinski
Janosch Machowinski
authored and
Janosch Machowinski
committed
chore: style and warning fixes
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent b452e49 commit 8f8aab8

File tree

3 files changed

+7
-31
lines changed

3 files changed

+7
-31
lines changed

rclcpp/include/rclcpp/wait_set_policies/dynamic_storage.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,7 @@ class DynamicStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCo
216216
shared_waitables_
217217
);
218218

219-
if(this->needs_pruning_) {
219+
if (this->needs_pruning_) {
220220
this->storage_prune_deleted_entities();
221221
this->needs_pruning_ = false;
222222
}

rclcpp/include/rclcpp/wait_set_policies/static_storage.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -166,8 +166,8 @@ class StaticStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCom
166166
// in case of invalid entries
167167

168168
throw std::runtime_error(
169-
"StaticStorage : storage_rebuild_rcl_wait_set: Detected"
170-
" invalid entity in static entity storage");
169+
"StaticStorage::storage_rebuild_rcl_wait_set(): entity weak_ptr "
170+
"unexpectedly expired in static entity storage");
171171
}
172172
}
173173

rclcpp/test/rclcpp/executors/test_executors.cpp

+4-28
Original file line numberDiff line numberDiff line change
@@ -917,9 +917,6 @@ TYPED_TEST(TestExecutors, dropSomeTimer)
917917

918918
const auto cur_time = std::chrono::steady_clock::now();
919919
ASSERT_LT(cur_time, max_end_time);
920-
if(cur_time > max_end_time) {
921-
return;
922-
}
923920
}
924921

925922
// delete timer 2. Note, the executor uses an unordered map internally, to order
@@ -937,9 +934,6 @@ TYPED_TEST(TestExecutors, dropSomeTimer)
937934

938935
const auto cur_time = std::chrono::steady_clock::now();
939936
ASSERT_LT(cur_time, max_end_time);
940-
if(cur_time > max_end_time) {
941-
return;
942-
}
943937
}
944938

945939
ASSERT_TRUE(timer1_works || timer2_works);
@@ -974,9 +968,6 @@ TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)
974968

975969
const auto cur_time = std::chrono::steady_clock::now();
976970
ASSERT_LT(cur_time, max_end_time);
977-
if(cur_time > max_end_time) {
978-
return;
979-
}
980971
}
981972

982973
// delete node 1.
@@ -990,9 +981,6 @@ TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)
990981

991982
const auto cur_time = std::chrono::steady_clock::now();
992983
ASSERT_LT(cur_time, max_end_time);
993-
if(cur_time > max_end_time) {
994-
return;
995-
}
996984
}
997985

998986
ASSERT_TRUE(timer2_works);
@@ -1009,11 +997,11 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)
1009997
bool sub2_works = false;
1010998

1011999
auto sub1 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1012-
[&sub1_works](const test_msgs::msg::Empty & msg) {
1000+
[&sub1_works](const test_msgs::msg::Empty &) {
10131001
sub1_works = true;
10141002
});
10151003
auto sub2 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1016-
[&sub2_works](const test_msgs::msg::Empty & msg) {
1004+
[&sub2_works](const test_msgs::msg::Empty &) {
10171005
sub2_works = true;
10181006
});
10191007

@@ -1031,9 +1019,6 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)
10311019

10321020
const auto cur_time = std::chrono::steady_clock::now();
10331021
ASSERT_LT(cur_time, max_end_time);
1034-
if(cur_time > max_end_time) {
1035-
return;
1036-
}
10371022
}
10381023

10391024
// delete subscription 2. Note, the executor uses an unordered map internally, to order
@@ -1053,9 +1038,6 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)
10531038

10541039
const auto cur_time = std::chrono::steady_clock::now();
10551040
ASSERT_LT(cur_time, max_end_time);
1056-
if(cur_time > max_end_time) {
1057-
return;
1058-
}
10591041
}
10601042

10611043
ASSERT_TRUE(sub1_works || sub2_works);
@@ -1074,11 +1056,11 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
10741056
bool sub2_works = false;
10751057

10761058
auto sub1 = node1->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1077-
[&sub1_works](const test_msgs::msg::Empty & msg) {
1059+
[&sub1_works](const test_msgs::msg::Empty &) {
10781060
sub1_works = true;
10791061
});
10801062
auto sub2 = node2->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1081-
[&sub2_works](const test_msgs::msg::Empty & msg) {
1063+
[&sub2_works](const test_msgs::msg::Empty &) {
10821064
sub2_works = true;
10831065
});
10841066

@@ -1098,9 +1080,6 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
10981080

10991081
const auto cur_time = std::chrono::steady_clock::now();
11001082
ASSERT_LT(cur_time, max_end_time);
1101-
if(cur_time > max_end_time) {
1102-
return;
1103-
}
11041083
}
11051084

11061085
// delete node 2.
@@ -1116,9 +1095,6 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
11161095

11171096
const auto cur_time = std::chrono::steady_clock::now();
11181097
ASSERT_LT(cur_time, max_end_time);
1119-
if(cur_time > max_end_time) {
1120-
return;
1121-
}
11221098
}
11231099

11241100
ASSERT_TRUE(sub1_works);

0 commit comments

Comments
 (0)