Skip to content

Commit 8e3be92

Browse files
Construct TF listeners passing nodes, spinning on separate thread (#5406) (#5432)
* Construct TF listeners passing nodes, spinning on separate thread * (tentative) pin down of the impacting change --------- (cherry picked from commit 1468484) Signed-off-by: Patrick Roncagliolo <[email protected]> Co-authored-by: Patrick Roncagliolo <[email protected]>
1 parent 06081c3 commit 8e3be92

File tree

8 files changed

+8
-8
lines changed

8 files changed

+8
-8
lines changed

nav2_amcl/src/amcl_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1510,7 +1510,7 @@ AmclNode::initTransforms()
15101510
get_node_timers_interface(),
15111511
callback_group_);
15121512
tf_buffer_->setCreateTimerInterface(timer_interface);
1513-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
1513+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
15141514
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
15151515

15161516
sent_first_transform_ = false;

nav2_behaviors/src/behavior_server.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ BehaviorServer::on_configure(const rclcpp_lifecycle::State & state)
8787
get_node_base_interface(),
8888
get_node_timers_interface());
8989
tf_->setCreateTimerInterface(timer_interface);
90-
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
90+
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
9191

9292
behavior_types_.resize(behavior_ids_.size());
9393
if (!loadBehaviorPlugins()) {

nav2_bt_navigator/src/bt_navigator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
6767
get_node_base_interface(), get_node_timers_interface());
6868
tf_->setCreateTimerInterface(timer_interface);
6969
tf_->setUsingDedicatedThread(true);
70-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
70+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
7171

7272
global_frame_ = get_parameter("global_frame").as_string();
7373
robot_frame_ = get_parameter("robot_base_frame").as_string();

nav2_collision_monitor/src/collision_detector_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ CollisionDetector::on_configure(const rclcpp_lifecycle::State & state)
5050
this->get_node_base_interface(),
5151
this->get_node_timers_interface());
5252
tf_buffer_->setCreateTimerInterface(timer_interface);
53-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
53+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
5454

5555
state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionDetectorState>(
5656
"collision_detector_state", rclcpp::SystemDefaultsQoS());

nav2_collision_monitor/src/collision_monitor_node.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & state)
5252
this->get_node_base_interface(),
5353
this->get_node_timers_interface());
5454
tf_buffer_->setCreateTimerInterface(timer_interface);
55-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
55+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
5656

5757
std::string cmd_vel_in_topic;
5858
std::string cmd_vel_out_topic;

nav2_docking/opennav_docking/src/docking_server.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
118118

119119
auto node = shared_from_this();
120120

121-
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_);
121+
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_, this, true);
122122
dock_db_->activate();
123123
navigator_->activate();
124124
vel_publisher_->on_activate();

nav2_route/src/route_server.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
3535
get_node_base_interface(),
3636
get_node_timers_interface());
3737
tf_->setCreateTimerInterface(timer_interface);
38-
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
38+
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
3939

4040
auto node = shared_from_this();
4141
graph_vis_publisher_ =

nav2_smoother/src/nav2_smoother.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
8080
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
8181
get_node_base_interface(), get_node_timers_interface());
8282
tf_->setCreateTimerInterface(timer_interface);
83-
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
83+
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
8484

8585
std::string costmap_topic, footprint_topic, robot_base_frame;
8686
double transform_tolerance = 0.1;

0 commit comments

Comments
 (0)