Skip to content

Commit

Permalink
Ensure dedicated_listener_thread_ is active in TransformListener::init
Browse files Browse the repository at this point in the history
  • Loading branch information
franciszhi committed May 23, 2023
1 parent 5eee548 commit 9a09cc3
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 1 deletion.
9 changes: 8 additions & 1 deletion tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,14 @@ 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();});
std::promise<void> promise;
dedicated_listener_thread_ = std::make_unique<std::thread>(
[&promise, this]()
{
promise.set_value();
executor_->spin();
});
promise.get_future().get();
// Tell the buffer we have a dedicated thread to enable timeouts
buffer_.setUsingDedicatedThread(true);
} else {
Expand Down
9 changes: 9 additions & 0 deletions tf2_ros/test/test_transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,15 @@ TEST(tf2_test_transform_listener, transform_listener_with_intraprocess)
custom_node->init_tf_listener();
}

TEST(tf2_test_transform_listener, transform_listener_spin_thread)
{
auto node = rclcpp::Node::make_shared("tf2_ros_message_filter");

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
tf2_ros::TransformListener tfl(buffer, node, true);
}

int main(int argc, char ** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down

0 comments on commit 9a09cc3

Please sign in to comment.