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

Added additional flag to fix race condition in TransformListener #518

Open
wants to merge 3 commits into
base: galactic
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
2 changes: 2 additions & 0 deletions tf2_ros/include/tf2_ros/transform_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include <memory>
#include <thread>
#include <utility>
#include <atomic>


namespace tf2_ros
Expand Down Expand Up @@ -155,6 +156,7 @@ class TransformListener
using thread_ptr =
std::unique_ptr<std::thread, std::function<void (std::thread *)>>;
thread_ptr dedicated_listener_thread_;
std::atomic_bool keep_running_;

rclcpp::Node::SharedPtr optional_default_node_ = nullptr;
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;
Expand Down
12 changes: 9 additions & 3 deletions tf2_ros/src/transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,19 +67,25 @@ void TransformListener::initThread(
{
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

keep_running_ = true;
// This lambda is required because `std::thread` cannot infer the correct
// rclcpp::spin, since there are more than one versions of it (overloaded).
// see: http://stackoverflow.com/a/27389714/671658
// I (wjwwood) chose to use the lamda rather than the static cast solution.
auto run_func =
[executor](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
[executor,
& keep_running =
keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
executor->add_node(node_base_interface);
executor->spin();
while (keep_running.load()) {
executor->spin_once();
}
executor->remove_node(node_base_interface);
};
dedicated_listener_thread_ = thread_ptr(
new std::thread(run_func, node_base_interface),
[executor](std::thread * t) {
[executor, & keep_running = keep_running_](std::thread * t) {
keep_running.store(false);
executor->cancel();
t->join();
delete t;
Expand Down
8 changes: 8 additions & 0 deletions tf2_ros/test/test_transform_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,14 @@ TEST(tf2_test_transform_listener, transform_listener_as_member)
custom_node->init_tf_listener();
}

TEST(tf2_test_transform_listener, transform_listener_should_destroy_correctly)
{
rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
tf2_ros::Buffer buffer(clock);
tf2_ros::TransformListener tfl(buffer, true);
(void) tfl;
}

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