From 3d0d51312ffefe7b46f4af0852527e4ef444ba94 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Mon, 28 Aug 2023 15:03:43 +0000 Subject: [PATCH 1/2] Remove unnecessary lambda captures in the tests. This was pointed out by compiling with clang. Signed-off-by: Chris Lalancette --- rclcpp/test/rclcpp/executors/test_events_executor.cpp | 10 +++++----- rclcpp/test/rclcpp/executors/test_executors.cpp | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/rclcpp/test/rclcpp/executors/test_events_executor.cpp b/rclcpp/test/rclcpp/executors/test_events_executor.cpp index fb5c9a5166..13092b7067 100644 --- a/rclcpp/test/rclcpp/executors/test_events_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_events_executor.cpp @@ -60,7 +60,7 @@ TEST_F(TestEventsExecutor, run_pub_sub) executor.add_node(node); bool spin_exited = false; - std::thread spinner([&spin_exited, &executor, this]() { + std::thread spinner([&spin_exited, &executor]() { executor.spin(); spin_exited = true; }); @@ -107,7 +107,7 @@ TEST_F(TestEventsExecutor, run_clients_servers) executor.add_node(node); bool spin_exited = false; - std::thread spinner([&spin_exited, &executor, this]() { + std::thread spinner([&spin_exited, &executor]() { executor.spin(); spin_exited = true; }); @@ -346,7 +346,7 @@ TEST_F(TestEventsExecutor, cancel_while_timers_running) }); - std::thread spinner([&executor, this]() {executor.spin();}); + std::thread spinner([&executor]() {executor.spin();}); std::this_thread::sleep_for(10ms); // Call cancel while t1 callback is still being executed @@ -373,7 +373,7 @@ TEST_F(TestEventsExecutor, cancel_while_timers_waiting) executor.add_node(node); auto start = std::chrono::steady_clock::now(); - std::thread spinner([&executor, this]() {executor.spin();}); + std::thread spinner([&executor]() {executor.spin();}); std::this_thread::sleep_for(10ms); executor.cancel(); @@ -395,7 +395,7 @@ TEST_F(TestEventsExecutor, destroy_entities) 2ms, [&]() {publisher->publish(std::make_unique());}); EventsExecutor executor_pub; executor_pub.add_node(node_pub); - std::thread spinner([&executor_pub, this]() {executor_pub.spin();}); + std::thread spinner([&executor_pub]() {executor_pub.spin();}); // Create a node with two different subscriptions to the topic auto node_sub = std::make_shared("node_sub"); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 0bd0bfcd49..99dee4274e 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -779,7 +779,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) { // that publishers aren't continuing to publish. // This was previously broken in that intraprocess guard conditions were only triggered on // publish and the test was added to prevent future regressions. - const size_t kNumMessages = 100; + constexpr size_t kNumMessages = 100; using ExecutorType = TypeParam; ExecutorType executor; @@ -808,7 +808,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) { // Fire a timer every 10ms up to 5 seconds waiting for subscriptions to be read. loops = 0; auto timer = this->node->create_wall_timer( - std::chrono::milliseconds(10), [this, &executor, &loops, &kNumMessages]() { + std::chrono::milliseconds(10), [this, &executor, &loops]() { loops++; if (kNumMessages == this->callback_count.load() || loops == 500) From 295b37f1007762f330419622facdf598db79b67b Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Mon, 28 Aug 2023 16:41:29 +0000 Subject: [PATCH 2/2] Switch to a static constexpr to try and make Windows happy. Signed-off-by: Chris Lalancette --- rclcpp/test/rclcpp/executors/test_executors.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 99dee4274e..fbd410bcab 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -779,7 +779,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) { // that publishers aren't continuing to publish. // This was previously broken in that intraprocess guard conditions were only triggered on // publish and the test was added to prevent future regressions. - constexpr size_t kNumMessages = 100; + static constexpr size_t kNumMessages = 100; using ExecutorType = TypeParam; ExecutorType executor; @@ -810,9 +810,7 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) { auto timer = this->node->create_wall_timer( std::chrono::milliseconds(10), [this, &executor, &loops]() { loops++; - if (kNumMessages == this->callback_count.load() || - loops == 500) - { + if (kNumMessages == this->callback_count.load() || loops == 500) { executor.cancel(); } });