Skip to content

Commit 560e756

Browse files
BriceRenaudeaujwallace42
authored andcommitted
[nav2_planner] Fix costmap thread reset on cleanup (ros-navigation#3548)
* remove costmap thread reset on cleanup * Init costmap thread in on_configure method * Move costmap_thread init in on_configure method
1 parent 3269ada commit 560e756

File tree

2 files changed

+5
-4
lines changed

2 files changed

+5
-4
lines changed

nav2_controller/src/controller_server.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -65,8 +65,6 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options)
6565
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
6666
"local_costmap", std::string{get_namespace()}, "local_costmap",
6767
get_parameter("use_sim_time").as_bool());
68-
// Launch a thread to run the costmap node
69-
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
7068
}
7169

7270
ControllerServer::~ControllerServer()
@@ -124,6 +122,8 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
124122
get_parameter("failure_tolerance", failure_tolerance_);
125123

126124
costmap_ros_->configure();
125+
// Launch a thread to run the costmap node
126+
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
127127

128128
try {
129129
progress_checker_type_ = nav2_util::get_plugin_type_param(node, progress_checker_id_);

nav2_planner/src/planner_server.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,6 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
6464
costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
6565
"global_costmap", std::string{get_namespace()}, "global_costmap",
6666
get_parameter("use_sim_time").as_bool());
67-
// Launch a thread to run the costmap node
68-
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
6967
}
7068

7169
PlannerServer::~PlannerServer()
@@ -86,6 +84,9 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
8684
costmap_ros_->configure();
8785
costmap_ = costmap_ros_->getCostmap();
8886

87+
// Launch a thread to run the costmap node
88+
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
89+
8990
RCLCPP_DEBUG(
9091
get_logger(), "Costmap size: %d,%d",
9192
costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY());

0 commit comments

Comments
 (0)