From a38fe792c95efc26c1c5c2dc80d749bf9d28f9a8 Mon Sep 17 00:00:00 2001 From: Michael Heine Date: Thu, 16 Jan 2025 16:05:49 +0000 Subject: [PATCH] Fixed deadlock in destructor in TransformListener --- tf2_ros/include/tf2_ros/transform_listener.h | 10 +++++++++- tf2_ros/src/transform_listener.cpp | 1 + 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/tf2_ros/include/tf2_ros/transform_listener.h b/tf2_ros/include/tf2_ros/transform_listener.h index 4f5e5eaf5..e9ba1a7f2 100644 --- a/tf2_ros/include/tf2_ros/transform_listener.h +++ b/tf2_ros/include/tf2_ros/transform_listener.h @@ -32,6 +32,7 @@ #ifndef TF2_ROS__TRANSFORM_LISTENER_H_ #define TF2_ROS__TRANSFORM_LISTENER_H_ +#include #include #include #include @@ -211,7 +212,13 @@ class TransformListener // Create executor with dedicated thread to spin. executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, node_base_interface_); - dedicated_listener_thread_ = std::make_unique([&]() {executor_->spin();}); + running_.store(true); + dedicated_listener_thread_ = std::make_unique( + [&]() { + while (running_.load()) { + executor_->spin_once(); + } + }); // Tell the buffer we have a dedicated thread to enable timeouts buffer_.setUsingDedicatedThread(true); } else { @@ -229,6 +236,7 @@ class TransformListener } } + std::atomic running_; bool spin_thread_{false}; std::unique_ptr dedicated_listener_thread_ {nullptr}; rclcpp::Executor::SharedPtr executor_ {nullptr}; diff --git a/tf2_ros/src/transform_listener.cpp b/tf2_ros/src/transform_listener.cpp index 55e946496..b83d8c5cb 100644 --- a/tf2_ros/src/transform_listener.cpp +++ b/tf2_ros/src/transform_listener.cpp @@ -71,6 +71,7 @@ TransformListener::TransformListener(tf2::BufferCore & buffer, bool spin_thread, TransformListener::~TransformListener() { if (spin_thread_) { + running_.store(false); executor_->cancel(); dedicated_listener_thread_->join(); }