Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 21 additions & 2 deletions nav2_controller/src/controller_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <utility>
#include <limits>

#include "lifecycle_msgs/msg/state.hpp"
#include "nav2_core/exceptions.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav_2d_utils/tf_help.hpp"
Expand Down Expand Up @@ -245,7 +246,19 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
for (it = controllers_.begin(); it != controllers_.end(); ++it) {
it->second->deactivate();
}
costmap_ros_->deactivate();

/*
* The costmap is also a lifecycle node, so it may have already fired on_deactivate
* via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
* in the order added, the preshutdown callbacks clearly don't per se, due to using an
* unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
* ordering assumption: https://github.com/ros2/rclcpp/issues/2096
*/
if (costmap_ros_->get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
costmap_ros_->deactivate();
}

publishZeroVelocity();
vel_publisher_->on_deactivate();
Expand All @@ -270,11 +283,17 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
controllers_.clear();

goal_checkers_.clear();
costmap_ros_->cleanup();

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

// Release any allocated resources
action_server_.reset();
odom_sub_.reset();
costmap_thread_.reset();
vel_publisher_.reset();
speed_limit_sub_.reset();

Expand Down
38 changes: 23 additions & 15 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,14 +272,18 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
RCLCPP_INFO(get_logger(), "Deactivating");

dyn_params_handler.reset();
costmap_publisher_->on_deactivate();
footprint_pub_->on_deactivate();

stop();

// Map thread stuff
map_update_thread_shutdown_ = true;
map_update_thread_->join();

if (map_update_thread_->joinable()) {
map_update_thread_->join();
}

costmap_publisher_->on_deactivate();
footprint_pub_->on_deactivate();

return nav2_util::CallbackReturn::SUCCESS;
}
Expand Down Expand Up @@ -529,18 +533,22 @@ void
Costmap2DROS::stop()
{
stop_updates_ = true;
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();
// unsubscribe from topics
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
plugin != plugins->end(); ++plugin)
{
(*plugin)->deactivate();
}
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
filter != filters->end(); ++filter)
{
(*filter)->deactivate();
// layered_costmap_ is set only if on_configure has been called
if (layered_costmap_) {
std::vector<std::shared_ptr<Layer>> * plugins = layered_costmap_->getPlugins();
std::vector<std::shared_ptr<Layer>> * filters = layered_costmap_->getFilters();

// unsubscribe from topics
for (std::vector<std::shared_ptr<Layer>>::iterator plugin = plugins->begin();
plugin != plugins->end(); ++plugin)
{
(*plugin)->deactivate();
}
for (std::vector<std::shared_ptr<Layer>>::iterator filter = filters->begin();
filter != filters->end(); ++filter)
{
(*filter)->deactivate();
}
}
initialized_ = false;
stopped_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,13 @@ class LifecycleManager : public rclcpp::Node
*/
bool resume();

/**
* @brief Perform preshutdown activities before our Context is shutdown.
* Note that this is related to our Context's shutdown sequence, not the
* lifecycle node state machine or shutdown().
*/
void onRclPreshutdown();

// Support function for creating service clients
/**
* @brief Support function for creating service clients
Expand Down Expand Up @@ -186,6 +193,14 @@ class LifecycleManager : public rclcpp::Node
*/
void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);

/**
* Register our preshutdown callback for this Node's rcl Context.
* The callback fires before this Node's Context is shutdown.
* Note this is not directly related to the lifecycle state machine or the
* shutdown() instance function.
*/
void registerRclPreshutdownCallback();

// Timer thread to look at bond connections
rclcpp::TimerBase::SharedPtr init_timer_;
rclcpp::TimerBase::SharedPtr bond_timer_;
Expand Down
31 changes: 31 additions & 0 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
declare_parameter("bond_respawn_max_duration", 10.0);
declare_parameter("attempt_respawn_reconnection", true);

registerRclPreshutdownCallback();

node_names_ = get_parameter("node_names").as_string_array();
get_parameter("autostart", autostart_);
double bond_timeout_s;
Expand Down Expand Up @@ -378,6 +380,35 @@ LifecycleManager::destroyBondTimer()
}
}

void
LifecycleManager::onRclPreshutdown()
{
RCLCPP_INFO(
get_logger(), "Running Nav2 LifecycleManager rcl preshutdown (%s)",
this->get_name());

destroyBondTimer();

/*
* Dropping the bond map is what we really need here, but we drop the others
* to prevent the bond map being used. Likewise, squash the service thread.
*/
service_thread_.reset();
node_names_.clear();
node_map_.clear();
bond_map_.clear();
}

void
LifecycleManager::registerRclPreshutdownCallback()
{
rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();

context->add_pre_shutdown_callback(
std::bind(&LifecycleManager::onRclPreshutdown, this)
);
}

void
LifecycleManager::checkBondConnections()
{
Expand Down
32 changes: 30 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 @@ -66,6 +67,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,19 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
action_server_pose_->deactivate();
action_server_poses_->deactivate();
plan_publisher_->on_deactivate();
costmap_ros_->deactivate();

/*
* The costmap is also a lifecycle node, so it may have already fired on_deactivate
* via rcl preshutdown cb. Despite the rclcpp docs saying on_shutdown callbacks fire
* in the order added, the preshutdown callbacks clearly don't per se, due to using an
* unordered_set iteration. Once this issue is resolved, we can maybe make a stronger
* ordering assumption: https://github.com/ros2/rclcpp/issues/2096
*/
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 +235,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
20 changes: 20 additions & 0 deletions nav2_util/include/nav2_util/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,13 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
return nav2_util::CallbackReturn::SUCCESS;
}

/**
* @brief Perform preshutdown activities before our Context is shutdown.
* Note that this is related to our Context's shutdown sequence, not the
* lifecycle node state machine.
*/
virtual void on_rcl_preshutdown();

/**
* @brief Create bond connection to lifecycle manager
*/
Expand All @@ -183,6 +190,19 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
*/
void printLifecycleNodeNotification();

/**
* Register our preshutdown callback for this Node's rcl Context.
* The callback fires before this Node's Context is shutdown.
* Note this is not directly related to the lifecycle state machine.
*/
void register_rcl_preshutdown_callback();
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> rcl_preshutdown_cb_handle_{nullptr};

/**
* Run some common cleanup steps shared between rcl preshutdown and destruction.
*/
void runCleanups();

// Connection to tell that server is still up
std::unique_ptr<bond::Bond> bond_{nullptr};
};
Expand Down
56 changes: 50 additions & 6 deletions nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,17 +36,20 @@ LifecycleNode::LifecycleNode(
bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true));

printLifecycleNodeNotification();

register_rcl_preshutdown_callback();
}

LifecycleNode::~LifecycleNode()
{
RCLCPP_INFO(get_logger(), "Destroying");
// In case this lifecycle node wasn't properly shut down, do it here
if (get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
on_deactivate(get_current_state());
on_cleanup(get_current_state());

runCleanups();

if (rcl_preshutdown_cb_handle_) {
rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
context->remove_pre_shutdown_callback(*(rcl_preshutdown_cb_handle_.get()));
rcl_preshutdown_cb_handle_.reset();
}
}

Expand All @@ -64,6 +67,47 @@ void LifecycleNode::createBond()
bond_->start();
}

void LifecycleNode::runCleanups()
{
/*
* In case this lifecycle node wasn't properly shut down, do it here.
* We will give the user some ability to clean up properly here, but it's
* best effort; i.e. we aren't trying to account for all possible states.
*/
if (get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
this->deactivate();
}

if (get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
this->cleanup();
}
}

void LifecycleNode::on_rcl_preshutdown()
{
RCLCPP_INFO(
get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)",
this->get_name());

runCleanups();

destroyBond();
}

void LifecycleNode::register_rcl_preshutdown_callback()
{
rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();

rcl_preshutdown_cb_handle_ = std::make_unique<rclcpp::PreShutdownCallbackHandle>(
context->add_pre_shutdown_callback(
std::bind(&LifecycleNode::on_rcl_preshutdown, this))
);
}

void LifecycleNode::destroyBond()
{
RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name());
Expand Down
36 changes: 36 additions & 0 deletions nav2_util/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,3 +47,39 @@ TEST(LifecycleNode, MultipleRclcppNodesExitCleanly)
std::this_thread::sleep_for(std::chrono::seconds(1));
SUCCEED();
}

TEST(LifecycleNode, OnPreshutdownCbFires)
{
// Ensure the on_rcl_preshutdown_cb fires

class MyNodeType : public nav2_util::LifecycleNode
{
public:
MyNodeType(
const std::string & node_name)
: nav2_util::LifecycleNode(node_name) {}

bool fired = false;

protected:
void on_rcl_preshutdown() override
{
fired = true;

nav2_util::LifecycleNode::on_rcl_preshutdown();
}
};

auto node = std::make_shared<MyNodeType>("test_node");

ASSERT_EQ(node->fired, false);

rclcpp::shutdown();

ASSERT_EQ(node->fired, true);

// Fire dtor to ensure nothing insane happens, e.g. exceptions.
node.reset();

SUCCEED();
}