Skip to content

TransformListener hangs in destructor when using dedicated thread #517

@zygfrydw

Description

@zygfrydw

Bug report

Required Info:

  • Operating System:
    • all systems, detected on Docker + Ubuntu 20.04
  • Installation type:
    • from binaries
  • Version or commit hash:
    • galactic
  • DDS implementation:
    • cyclone dds
  • Client library (if applicable):
    • N/A

Steps to reproduce issue

I have noticed timeouts in my unit tests for node using TransformListener because o TransformListener hangs on destructor.
Here is a simple test:

#include <gtest/gtest.h>
#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>

class MyNode : public rclcpp::Node
{
public:
  explicit MyNode(const rclcpp::NodeOptions& options) 
  : rclcpp::Node::Node("MyNode"),
  tf_buffer_(this->get_clock()),
  tf_listener_(this->tf_buffer_)
  {
  }

  virtual ~MyNode(){}

private:
  tf2_ros::Buffer tf_buffer_;
  tf2_ros::TransformListener tf_listener_;
};

TEST_F(MyNodeTest, I_should_have_renamed_this_test) {
  if (!rclcpp::ok()) {
    rclcpp::init(0, nullptr);
  }
  {
    auto my_node = std::make_unique<MyNode>();
    // Do some test with MyNode
  }
  // The test will block here and wait indefinatelly because of bug in tf_listener destructor
}

Expected behaviour

Execution will not block on TransformListener destructor indefinitely.

Actual behavior

Execution blocks on TransformListener destructor indefinitely.

Additional information

This bug is caused by race condition with running and stopping SingleTreadedThreadSafeExecutor in TransformListener.
The current implementation is:

auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
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),
[executor](std::thread * t) {
    executor->cancel();
    t->join();
    delete t;
});

If the dedicated_listener_thread_ is not able to run before main thread enters destructor for TransformListener the destructor hangs because dedicated_listener_thread_ is spinning.
The order of execution is as follow:

  1. main thread creates dedicated_listener_thread_
  2. main thread perform all its jobs and TransformListener destructor
  3. Main thread in TransformListener destructor calls executor->cancel() which sets executor.spinning = false
  4. Main thread waits for dedicated_listener_thread_ to finish
  5. Dedicated thread starts running and calls executor-spin()
  6. Dedicated thread at the beginning of executor->spin() sets executor.spinning = true
  7. Dedicated thread is spinning waiting for messages or cancel which will not happen because main thread is blocked in t->join();

Metadata

Metadata

Assignees

Labels

No labels
No labels

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions