Skip to content

Commit

Permalink
Uncrustify transform_listener
Browse files Browse the repository at this point in the history
  • Loading branch information
Zygfryd Wieszok committed Apr 14, 2022
1 parent 743766a commit 72e5d8b
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
1 change: 0 additions & 1 deletion tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,6 @@
#include <tf2/time.h>
#include <tf2_ros/visibility_control.h>

#include <atomic>
#include <tf2_msgs/msg/tf_message.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down
9 changes: 5 additions & 4 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,17 +73,18 @@ void TransformListener::initThread(
// see: http://stackoverflow.com/a/27389714/671658
// I (wjwwood) chose to use the lamda rather than the static cast solution.
auto run_func =
[executor, &keep_running =keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
[executor,
& keep_running =
keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
executor->add_node(node_base_interface);
while(keep_running.load())
{
while(keep_running.load()){
executor->spin_once();
}
executor->remove_node(node_base_interface);
};
dedicated_listener_thread_ = thread_ptr(
new std::thread(run_func, node_base_interface),
[executor, &keep_running = keep_running_](std::thread * t) {
[executor, & keep_running = keep_running_](std::thread * t) {
keep_running.store(false);
executor->cancel();
t->join();
Expand Down

0 comments on commit 72e5d8b

Please sign in to comment.