Skip to content

Commit

Permalink
Ensure executor_ is spinning in TransformListener::init
Browse files Browse the repository at this point in the history
  • Loading branch information
franciszhi committed Jun 28, 2023
1 parent 5eee548 commit 44c7942
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 0 deletions.
3 changes: 3 additions & 0 deletions tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -211,6 +211,9 @@ class TransformListener
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();});
while (!executor_->is_spinning()) {
std::this_thread::sleep_for(std::chrono::microseconds(10));
}
// 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 44c7942

Please sign in to comment.