Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixed deadlock in destructor in TransformListener #752

Open
wants to merge 1 commit into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 9 additions & 1 deletion tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#ifndef TF2_ROS__TRANSFORM_LISTENER_H_
#define TF2_ROS__TRANSFORM_LISTENER_H_

#include <atomic>
#include <functional>
#include <memory>
#include <thread>
Expand Down Expand Up @@ -211,7 +212,13 @@ class TransformListener
// Create executor with dedicated thread to spin.
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
executor_->add_callback_group(callback_group_, node_base_interface_);
dedicated_listener_thread_ = std::make_unique<std::thread>([&]() {executor_->spin();});
running_.store(true);
dedicated_listener_thread_ = std::make_unique<std::thread>(
[&]() {
while (running_.load()) {
executor_->spin_once();
}
});
// Tell the buffer we have a dedicated thread to enable timeouts
buffer_.setUsingDedicatedThread(true);
} else {
Expand All @@ -229,6 +236,7 @@ class TransformListener
}
}

std::atomic<bool> running_;
bool spin_thread_{false};
std::unique_ptr<std::thread> dedicated_listener_thread_ {nullptr};
rclcpp::Executor::SharedPtr executor_ {nullptr};
Expand Down
1 change: 1 addition & 0 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ TransformListener::TransformListener(tf2::BufferCore & buffer, bool spin_thread,
TransformListener::~TransformListener()
{
if (spin_thread_) {
running_.store(false);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I find it very surprising that this pattern is needed, as it is (essentially) the same as what executor_->cancel() should be doing under the hood. I'm going to see if I can reproduce against jammy/rolling.

executor_->cancel();
dedicated_listener_thread_->join();
}
Expand Down