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 <[email protected]>
  • Loading branch information
mbryan committed Jan 27, 2023
1 parent e772604 commit f2a6d02
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 1 deletion.
7 changes: 7 additions & 0 deletions nav2_planner/include/nav2_planner/planner_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,6 +189,13 @@ class PlannerServer : public nav2_util::LifecycleNode
*/
void computePlan();

/**
* @brief Perform destruction activity also performed by rcl preshutdown.
*/
void prepDestruction();

void on_rcl_preshutdown() override;

/**
* @brief The action server callback which calls planner to get the path
* ComputePathThroughPoses
Expand Down
15 changes: 14 additions & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,12 +67,25 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options)
costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_);
}

PlannerServer::~PlannerServer()
void
PlannerServer::prepDestruction()
{
planners_.clear();
costmap_thread_.reset();
}

PlannerServer::~PlannerServer()
{
prepDestruction();
}


void PlannerServer::on_rcl_preshutdown()
{
prepDestruction();
LifecycleNode::on_rcl_preshutdown();
}

nav2_util::CallbackReturn
PlannerServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
Expand Down

0 comments on commit f2a6d02

Please sign in to comment.