Skip to content

Commit 933609a

Browse files
author
Zygfryd Wieszok
committed
Uncrustify transform_listener
1 parent 743766a commit 933609a

File tree

2 files changed

+5
-5
lines changed

2 files changed

+5
-5
lines changed

tf2_ros/include/tf2_ros/transform_listener.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,6 @@
3636
#include <tf2/time.h>
3737
#include <tf2_ros/visibility_control.h>
3838

39-
#include <atomic>
4039
#include <tf2_msgs/msg/tf_message.hpp>
4140
#include <rclcpp/rclcpp.hpp>
4241

tf2_ros/src/transform_listener.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,17 +73,18 @@ void TransformListener::initThread(
7373
// see: http://stackoverflow.com/a/27389714/671658
7474
// I (wjwwood) chose to use the lamda rather than the static cast solution.
7575
auto run_func =
76-
[executor, &keep_running =keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
76+
[executor,
77+
& keep_running =
78+
keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
7779
executor->add_node(node_base_interface);
78-
while(keep_running.load())
79-
{
80+
while (keep_running.load()) {
8081
executor->spin_once();
8182
}
8283
executor->remove_node(node_base_interface);
8384
};
8485
dedicated_listener_thread_ = thread_ptr(
8586
new std::thread(run_func, node_base_interface),
86-
[executor, &keep_running = keep_running_](std::thread * t) {
87+
[executor, & keep_running = keep_running_](std::thread * t) {
8788
keep_running.store(false);
8889
executor->cancel();
8990
t->join();

0 commit comments

Comments
 (0)