Skip to content

Commit

Permalink
Ensure that we break bonds in lifecycle node/manager prior to rcl_shu…
Browse files Browse the repository at this point in the history
…tdown.

Partial fix for Issue ros-navigation#3271

Signed-off-by: mbryan <matthew.bryan@dell.com>
  • Loading branch information
mbryan committed Jan 29, 2023
1 parent e75612f commit b3b548d
Show file tree
Hide file tree
Showing 5 changed files with 137 additions and 4 deletions.
19 changes: 17 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/controller_exceptions.hpp"
#include "nav_2d_utils/conversions.hpp"
#include "nav_2d_utils/tf_help.hpp"
Expand Down Expand Up @@ -246,7 +247,16 @@ 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. Let's not make an assumption about the order these fire...
*/
if (costmap_ros_->get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
{
costmap_ros_->deactivate();
}

publishZeroVelocity();
vel_publisher_->on_deactivate();
Expand All @@ -271,11 +281,16 @@ 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
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
15 changes: 15 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,14 @@ 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};

// Connection to tell that server is still up
std::unique_ptr<bond::Bond> bond_{nullptr};
};
Expand Down
61 changes: 59 additions & 2 deletions nav2_util/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,17 +36,32 @@ 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());
this->deactivate();
}

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

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();
destroyBond();
}
}

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

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

/*
* 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();
}


/*
* A child class may destroyBond(), but we do it here in case it didn't.
* We don't want to *require* the author of the child class to know they
* need to clean the bond up.
*/
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

0 comments on commit b3b548d

Please sign in to comment.