From 41608622dc047c0e40db709fb36fd23b4511d9fc Mon Sep 17 00:00:00 2001 From: bpwilcox Date: Wed, 24 Jul 2019 11:18:58 -0700 Subject: [PATCH] capture local executor in lambda --- tf2_ros/src/transform_listener.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/tf2_ros/src/transform_listener.cpp b/tf2_ros/src/transform_listener.cpp index 76d9b6b70..94908b9b3 100644 --- a/tf2_ros/src/transform_listener.cpp +++ b/tf2_ros/src/transform_listener.cpp @@ -54,27 +54,27 @@ TransformListener::TransformListener(tf2::BufferCore & buffer, bool spin_thread) TransformListener::~TransformListener() { - if (executor_) { - executor_->cancel(); - } } void TransformListener::initThread( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) { - executor_ = std::make_unique(); + auto executor = std::make_shared(); + // This lambda is required because `std::thread` cannot infer the correct // rclcpp::spin, since there are more than one versions of it (overloaded). // see: http://stackoverflow.com/a/27389714/671658 // I (wjwwood) chose to use the lamda rather than the static cast solution. - auto run_func = [&](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) { - executor_->add_node(node_base_interface); - executor_->spin(); - executor_->remove_node(node_base_interface); + auto run_func = + [executor](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) { + executor->add_node(node_base_interface); + executor->spin(); + executor->remove_node(node_base_interface); }; dedicated_listener_thread_ = thread_ptr( new std::thread(run_func, node_base_interface), - [](std::thread * t) { + [executor](std::thread * t) { + executor->cancel(); t->join(); delete t; // TODO(tfoote) reenable callback queue processing