@@ -60,7 +60,7 @@ TEST_F(TestEventsExecutor, run_pub_sub)
6060 executor.add_node (node);
6161
6262 bool spin_exited = false ;
63- std::thread spinner ([&spin_exited, &executor, this ]() {
63+ std::thread spinner ([&spin_exited, &executor]() {
6464 executor.spin ();
6565 spin_exited = true ;
6666 });
@@ -107,7 +107,7 @@ TEST_F(TestEventsExecutor, run_clients_servers)
107107 executor.add_node (node);
108108
109109 bool spin_exited = false ;
110- std::thread spinner ([&spin_exited, &executor, this ]() {
110+ std::thread spinner ([&spin_exited, &executor]() {
111111 executor.spin ();
112112 spin_exited = true ;
113113 });
@@ -346,7 +346,7 @@ TEST_F(TestEventsExecutor, cancel_while_timers_running)
346346 });
347347
348348
349- std::thread spinner ([&executor, this ]() {executor.spin ();});
349+ std::thread spinner ([&executor]() {executor.spin ();});
350350
351351 std::this_thread::sleep_for (10ms);
352352 // Call cancel while t1 callback is still being executed
@@ -373,7 +373,7 @@ TEST_F(TestEventsExecutor, cancel_while_timers_waiting)
373373 executor.add_node (node);
374374
375375 auto start = std::chrono::steady_clock::now ();
376- std::thread spinner ([&executor, this ]() {executor.spin ();});
376+ std::thread spinner ([&executor]() {executor.spin ();});
377377
378378 std::this_thread::sleep_for (10ms);
379379 executor.cancel ();
@@ -395,7 +395,7 @@ TEST_F(TestEventsExecutor, destroy_entities)
395395 2ms, [&]() {publisher->publish (std::make_unique<test_msgs::msg::Empty>());});
396396 EventsExecutor executor_pub;
397397 executor_pub.add_node (node_pub);
398- std::thread spinner ([&executor_pub, this ]() {executor_pub.spin ();});
398+ std::thread spinner ([&executor_pub]() {executor_pub.spin ();});
399399
400400 // Create a node with two different subscriptions to the topic
401401 auto node_sub = std::make_shared<rclcpp::Node>(" node_sub" );
0 commit comments