Skip to content

Commit

Permalink
Ensure planner_server shuts down cleanly on SIGINT.
Browse files Browse the repository at this point in the history
Needed to ensure code coverage flushes. See Issue ros-navigation#3271.

Signed-off-by: mbryan <matthew.bryan@dell.com>
  • Loading branch information
mbryan committed Jan 28, 2023
1 parent 267691f commit 0c9a83b
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,10 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)

PlannerServer::~PlannerServer()
{
/*
* Backstop ensuring this state is destroyed, even if deactivate/cleanup are
* never called.
*/
planners_.clear();
costmap_thread_.reset();
}
Expand Down Expand Up @@ -224,7 +228,9 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
for (it = planners_.begin(); it != planners_.end(); ++it) {
it->second->cleanup();
}

planners_.clear();
costmap_thread_.reset();
costmap_ = nullptr;
return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down

0 comments on commit 0c9a83b

Please sign in to comment.