diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 71b50bdcc79..994e3d04ee9 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -1510,7 +1510,7 @@ AmclNode::initTransforms() get_node_timers_interface(), callback_group_); tf_buffer_->setCreateTimerInterface(timer_interface); - tf_listener_ = std::make_shared(*tf_buffer_); + tf_listener_ = std::make_shared(*tf_buffer_, this, true); tf_broadcaster_ = std::make_shared(shared_from_this()); sent_first_transform_ = false; diff --git a/nav2_behaviors/src/behavior_server.cpp b/nav2_behaviors/src/behavior_server.cpp index a04aea40315..69e99344c0f 100644 --- a/nav2_behaviors/src/behavior_server.cpp +++ b/nav2_behaviors/src/behavior_server.cpp @@ -87,7 +87,7 @@ BehaviorServer::on_configure(const rclcpp_lifecycle::State & state) get_node_base_interface(), get_node_timers_interface()); tf_->setCreateTimerInterface(timer_interface); - transform_listener_ = std::make_shared(*tf_); + transform_listener_ = std::make_shared(*tf_, this, true); behavior_types_.resize(behavior_ids_.size()); if (!loadBehaviorPlugins()) { diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 12047c2feef..f4b1e7de30e 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -67,7 +67,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state) get_node_base_interface(), get_node_timers_interface()); tf_->setCreateTimerInterface(timer_interface); tf_->setUsingDedicatedThread(true); - tf_listener_ = std::make_shared(*tf_, this, false); + tf_listener_ = std::make_shared(*tf_, this, true); global_frame_ = get_parameter("global_frame").as_string(); robot_frame_ = get_parameter("robot_base_frame").as_string(); diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index 7f87bc1bb92..8150671e165 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -50,7 +50,7 @@ CollisionDetector::on_configure(const rclcpp_lifecycle::State & state) this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_->setCreateTimerInterface(timer_interface); - tf_listener_ = std::make_shared(*tf_buffer_); + tf_listener_ = std::make_shared(*tf_buffer_, this, true); state_pub_ = this->create_publisher( "collision_detector_state", rclcpp::SystemDefaultsQoS()); diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 420d0268bbf..e19f71c745e 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -52,7 +52,7 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & state) this->get_node_base_interface(), this->get_node_timers_interface()); tf_buffer_->setCreateTimerInterface(timer_interface); - tf_listener_ = std::make_shared(*tf_buffer_); + tf_listener_ = std::make_shared(*tf_buffer_, this, true); std::string cmd_vel_in_topic; std::string cmd_vel_out_topic; diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index c14686ee1a5..c852d7d8d78 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -118,7 +118,7 @@ DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/) auto node = shared_from_this(); - tf2_listener_ = std::make_unique(*tf2_buffer_); + tf2_listener_ = std::make_unique(*tf2_buffer_, this, true); dock_db_->activate(); navigator_->activate(); vel_publisher_->on_activate(); diff --git a/nav2_route/src/route_server.cpp b/nav2_route/src/route_server.cpp index aad64e16ec6..10941a3cf03 100644 --- a/nav2_route/src/route_server.cpp +++ b/nav2_route/src/route_server.cpp @@ -35,7 +35,7 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) get_node_base_interface(), get_node_timers_interface()); tf_->setCreateTimerInterface(timer_interface); - transform_listener_ = std::make_shared(*tf_); + transform_listener_ = std::make_shared(*tf_, this, true); auto node = shared_from_this(); graph_vis_publisher_ = diff --git a/nav2_smoother/src/nav2_smoother.cpp b/nav2_smoother/src/nav2_smoother.cpp index b09b3171eb4..6ee027432f1 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -80,7 +80,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state) auto timer_interface = std::make_shared( get_node_base_interface(), get_node_timers_interface()); tf_->setCreateTimerInterface(timer_interface); - transform_listener_ = std::make_shared(*tf_); + transform_listener_ = std::make_shared(*tf_, this, true); std::string costmap_topic, footprint_topic, robot_base_frame; double transform_tolerance = 0.1;