Skip to content
Merged
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: 1 addition & 1 deletion nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1510,7 +1510,7 @@ AmclNode::initTransforms()
get_node_timers_interface(),
callback_group_);
tf_buffer_->setCreateTimerInterface(timer_interface);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());

sent_first_transform_ = false;
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/src/behavior_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::TransformListener>(*tf_);
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);

behavior_types_.resize(behavior_ids_.size());
if (!loadBehaviorPlugins()) {
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::TransformListener>(*tf_, this, false);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);

global_frame_ = get_parameter("global_frame").as_string();
robot_frame_ = get_parameter("robot_base_frame").as_string();
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/collision_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::TransformListener>(*tf_buffer_);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);

state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionDetectorState>(
"collision_detector_state", rclcpp::SystemDefaultsQoS());
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::TransformListener>(*tf_buffer_);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);

std::string cmd_vel_in_topic;
std::string cmd_vel_out_topic;
Expand Down
2 changes: 1 addition & 1 deletion nav2_docking/opennav_docking/src/docking_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/)

auto node = shared_from_this();

tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_);
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_, this, true);
dock_db_->activate();
navigator_->activate();
vel_publisher_->on_activate();
Expand Down
2 changes: 1 addition & 1 deletion nav2_route/src/route_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<tf2_ros::TransformListener>(*tf_);
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);

auto node = shared_from_this();
graph_vis_publisher_ =
Expand Down
2 changes: 1 addition & 1 deletion nav2_smoother/src/nav2_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
get_node_base_interface(), get_node_timers_interface());
tf_->setCreateTimerInterface(timer_interface);
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);

std::string costmap_topic, footprint_topic, robot_base_frame;
double transform_tolerance = 0.1;
Expand Down
Loading