Skip to content

Commit 743766a

Browse files
author
Zygfryd Wieszok
committed
Added additional flag to fix race condition in TransformListener
1 parent 5abe0e7 commit 743766a

File tree

2 files changed

+11
-3
lines changed

2 files changed

+11
-3
lines changed

tf2_ros/include/tf2_ros/transform_listener.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
#include <tf2/time.h>
3737
#include <tf2_ros/visibility_control.h>
3838

39+
#include <atomic>
3940
#include <tf2_msgs/msg/tf_message.hpp>
4041
#include <rclcpp/rclcpp.hpp>
4142

@@ -45,6 +46,7 @@
4546
#include <memory>
4647
#include <thread>
4748
#include <utility>
49+
#include <atomic>
4850

4951

5052
namespace tf2_ros
@@ -155,6 +157,7 @@ class TransformListener
155157
using thread_ptr =
156158
std::unique_ptr<std::thread, std::function<void (std::thread *)>>;
157159
thread_ptr dedicated_listener_thread_;
160+
std::atomic_bool keep_running_;
158161

159162
rclcpp::Node::SharedPtr optional_default_node_ = nullptr;
160163
rclcpp::Subscription<tf2_msgs::msg::TFMessage>::SharedPtr message_subscription_tf_;

tf2_ros/src/transform_listener.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -67,19 +67,24 @@ void TransformListener::initThread(
6767
{
6868
auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
6969

70+
keep_running_ = true;
7071
// This lambda is required because `std::thread` cannot infer the correct
7172
// rclcpp::spin, since there are more than one versions of it (overloaded).
7273
// see: http://stackoverflow.com/a/27389714/671658
7374
// I (wjwwood) chose to use the lamda rather than the static cast solution.
7475
auto run_func =
75-
[executor](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
76+
[executor, &keep_running =keep_running_](rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface) {
7677
executor->add_node(node_base_interface);
77-
executor->spin();
78+
while(keep_running.load())
79+
{
80+
executor->spin_once();
81+
}
7882
executor->remove_node(node_base_interface);
7983
};
8084
dedicated_listener_thread_ = thread_ptr(
8185
new std::thread(run_func, node_base_interface),
82-
[executor](std::thread * t) {
86+
[executor, &keep_running = keep_running_](std::thread * t) {
87+
keep_running.store(false);
8388
executor->cancel();
8489
t->join();
8590
delete t;

0 commit comments

Comments
 (0)