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

Ensure executor_ is spinning in TransformListener::init #605

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
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));
}
Comment on lines +214 to +216
Copy link
Contributor

Choose a reason for hiding this comment

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

May I ask what actually prompted this change, there's not a related issue nor pull request. Furthermore, when it comes to testing, a frozen node likely would've occured due to incorrect setup in the "main" section of the test file. Is it worth adding a more information needed tag?

// 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