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

Remove unnecessary lambda captures in the tests. #2289

Merged
merged 2 commits into from
Aug 28, 2023
Merged
Changes from 1 commit
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
10 changes: 5 additions & 5 deletions rclcpp/test/rclcpp/executors/test_events_executor.cpp
Original file line number Diff line number Diff line change
@@ -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<test_msgs::msg::Empty>());});
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<rclcpp::Node>("node_sub");
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
@@ -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)