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 29, 2023
1 parent 65e561f commit 0c3d50b
Showing 1 changed file with 23 additions and 2 deletions.
25 changes: 23 additions & 2 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <utility>

#include "builtin_interfaces/msg/duration.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "nav2_util/costmap.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
Expand Down Expand Up @@ -69,6 +70,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 @@ -194,7 +199,12 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
action_server_pose_->deactivate();
action_server_poses_->deactivate();
plan_publisher_->on_deactivate();
costmap_ros_->deactivate();

if (costmap_ros_->get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
costmap_ros_->deactivate();
}

PlannerMap::iterator it;
for (it = planners_.begin(); it != planners_.end(); ++it) {
Expand All @@ -218,13 +228,24 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
action_server_poses_.reset();
plan_publisher_.reset();
tf_.reset();
costmap_ros_->cleanup();

/*
* Double check whether something else transitioned it to INACTIVE
* already, e.g. the rcl preshutdown callback.
*/
if (costmap_ros_->get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
costmap_ros_->cleanup();
}

PlannerMap::iterator it;
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 0c3d50b

Please sign in to comment.