Skip to content

Commit 1468484

Browse files
authored
Construct TF listeners passing nodes, spinning on separate thread (#5406)
* Construct TF listeners passing nodes, spinning on separate thread Signed-off-by: Patrick Roncagliolo <ronca.pat@gmail.com> * (tentative) pin down of the impacting change Signed-off-by: Patrick Roncagliolo <ronca.pat@gmail.com> --------- Signed-off-by: Patrick Roncagliolo <ronca.pat@gmail.com>
1 parent 9cd0f9f commit 1468484

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
@@ -1339,7 +1339,7 @@ AmclNode::initTransforms()
13391339
get_node_timers_interface(),
13401340
callback_group_);
13411341
tf_buffer_->setCreateTimerInterface(timer_interface);
1342-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
1342+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, true);
13431343
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(shared_from_this());
13441344

13451345
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
@@ -54,7 +54,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state)
5454
get_node_base_interface(), get_node_timers_interface());
5555
tf_->setCreateTimerInterface(timer_interface);
5656
tf_->setUsingDedicatedThread(true);
57-
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
57+
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
5858

5959
global_frame_ = this->declare_or_get_parameter("global_frame", std::string("map"));
6060
robot_frame_ = this->declare_or_get_parameter("robot_base_frame", std::string("base_link"));

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");

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
@@ -121,7 +121,7 @@ DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/)
121121

122122
auto node = shared_from_this();
123123

124-
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_);
124+
tf2_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf2_buffer_, this, true);
125125
dock_db_->activate();
126126
navigator_->activate();
127127
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
@@ -78,7 +78,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state)
7878
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
7979
get_node_base_interface(), get_node_timers_interface());
8080
tf_->setCreateTimerInterface(timer_interface);
81-
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
81+
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, true);
8282

8383
std::string costmap_topic, footprint_topic, robot_base_frame;
8484
double transform_tolerance = 0.1;

0 commit comments

Comments
 (0)