diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 93b8f599a8d..b3b21631a59 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -1339,7 +1339,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 54ace7bac0a..0f4db4b3bf6 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 5f99c1452db..95d3c7dcaa7 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -54,7 +54,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_ = this->declare_or_get_parameter("global_frame", std::string("map")); robot_frame_ = this->declare_or_get_parameter("robot_base_frame", std::string("base_link")); diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index a45d35dc3cd..91023afae4f 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"); diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 7bff3a8a4d1..d7ec6131220 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 17dc1c28da3..1208ade5521 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -121,7 +121,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 2a44005111b..fee6bf7b671 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 66e3fd926ff..74714bafb81 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -78,7 +78,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;