16 #include "nav2_lifecycle_manager/lifecycle_manager.hpp"
23 #include "rclcpp/rclcpp.hpp"
25 using namespace std::chrono_literals;
26 using namespace std::placeholders;
28 using lifecycle_msgs::msg::Transition;
29 using lifecycle_msgs::msg::State;
32 namespace nav2_lifecycle_manager
35 LifecycleManager::LifecycleManager(
const rclcpp::NodeOptions & options)
36 : Node(
"lifecycle_manager", options), diagnostics_updater_(this)
38 RCLCPP_INFO(get_logger(),
"Creating");
42 declare_parameter(
"node_names", rclcpp::PARAMETER_STRING_ARRAY);
43 declare_parameter(
"autostart", rclcpp::ParameterValue(
false));
44 declare_parameter(
"bond_timeout", 4.0);
45 declare_parameter(
"service_timeout", 5.0);
46 declare_parameter(
"bond_respawn_max_duration", 10.0);
47 declare_parameter(
"attempt_respawn_reconnection",
true);
51 node_names_ = get_parameter(
"node_names").as_string_array();
52 get_parameter(
"autostart", autostart_);
53 double bond_timeout_s;
54 get_parameter(
"bond_timeout", bond_timeout_s);
55 bond_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(
56 std::chrono::duration<double>(bond_timeout_s));
58 double service_timeout_s;
59 get_parameter(
"service_timeout", service_timeout_s);
60 service_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(
61 std::chrono::duration<double>(service_timeout_s));
63 double respawn_timeout_s;
64 get_parameter(
"bond_respawn_max_duration", respawn_timeout_s);
65 bond_respawn_max_duration_ = rclcpp::Duration::from_seconds(respawn_timeout_s);
67 get_parameter(
"attempt_respawn_reconnection", attempt_respawn_reconnection_);
69 callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
false);
71 transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
72 transition_state_map_[Transition::TRANSITION_CLEANUP] = State::PRIMARY_STATE_UNCONFIGURED;
73 transition_state_map_[Transition::TRANSITION_ACTIVATE] = State::PRIMARY_STATE_ACTIVE;
74 transition_state_map_[Transition::TRANSITION_DEACTIVATE] = State::PRIMARY_STATE_INACTIVE;
75 transition_state_map_[Transition::TRANSITION_UNCONFIGURED_SHUTDOWN] =
76 State::PRIMARY_STATE_FINALIZED;
78 transition_label_map_[Transition::TRANSITION_CONFIGURE] = std::string(
"Configuring ");
79 transition_label_map_[Transition::TRANSITION_CLEANUP] = std::string(
"Cleaning up ");
80 transition_label_map_[Transition::TRANSITION_ACTIVATE] = std::string(
"Activating ");
81 transition_label_map_[Transition::TRANSITION_DEACTIVATE] = std::string(
"Deactivating ");
82 transition_label_map_[Transition::TRANSITION_UNCONFIGURED_SHUTDOWN] =
83 std::string(
"Shutting down ");
85 init_timer_ = this->create_wall_timer(
88 init_timer_->cancel();
92 init_timer_ = this->create_wall_timer(
95 init_timer_->cancel();
100 auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
101 executor->add_callback_group(callback_group_, get_node_base_interface());
102 service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
104 diagnostics_updater_.setHardwareID(
"Nav2");
110 RCLCPP_INFO(get_logger(),
"Destroying %s", get_name());
111 service_thread_.reset();
116 const std::shared_ptr<rmw_request_id_t>,
117 const std::shared_ptr<ManageLifecycleNodes::Request> request,
118 std::shared_ptr<ManageLifecycleNodes::Response> response)
120 switch (request->command) {
121 case ManageLifecycleNodes::Request::STARTUP:
124 case ManageLifecycleNodes::Request::CONFIGURE:
127 case ManageLifecycleNodes::Request::CLEANUP:
130 case ManageLifecycleNodes::Request::RESET:
131 response->success =
reset();
133 case ManageLifecycleNodes::Request::SHUTDOWN:
136 case ManageLifecycleNodes::Request::PAUSE:
137 response->success =
pause();
139 case ManageLifecycleNodes::Request::RESUME:
140 response->success =
resume();
148 return managed_nodes_state_ == NodeState::ACTIVE;
153 const std::shared_ptr<rmw_request_id_t>,
154 const std::shared_ptr<std_srvs::srv::Trigger::Request>,
155 std::shared_ptr<std_srvs::srv::Trigger::Response> response)
163 unsigned char error_level;
165 switch (managed_nodes_state_) {
166 case NodeState::ACTIVE:
167 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
168 message =
"Managed nodes are active";
170 case NodeState::INACTIVE:
171 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
172 message =
"Managed nodes are inactive";
174 case NodeState::UNCONFIGURED:
175 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
176 message =
"Managed nodes are unconfigured";
178 case NodeState::FINALIZED:
179 error_level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
180 message =
"Managed nodes have been shut down";
183 error_level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
184 message =
"An error has occurred during a node state transition";
187 stat.summary(error_level,
message);
193 message(
"Creating and initializing lifecycle service clients");
194 for (
auto & node_name : node_names_) {
195 node_map_[node_name] =
196 std::make_shared<LifecycleServiceClient>(node_name, shared_from_this());
203 message(
"Creating and initializing lifecycle service servers");
204 manager_srv_ = std::make_shared<nav2_util::ServiceServer<ManageLifecycleNodes>>(
205 get_name() + std::string(
"/manage_nodes"),
208 rclcpp::SystemDefaultsQoS(),
211 is_active_srv_ = std::make_shared<nav2_util::ServiceServer<std_srvs::srv::Trigger>>(
212 get_name() + std::string(
"/is_active"),
215 rclcpp::SystemDefaultsQoS(),
222 message(
"Destroying lifecycle service clients");
223 for (
auto & kv : node_map_) {
231 const double timeout_ns =
232 std::chrono::duration_cast<std::chrono::nanoseconds>(bond_timeout_).count();
233 const double timeout_s = timeout_ns / 1e9;
235 if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) {
236 bond_map_[node_name] =
237 std::make_shared<bond::Bond>(
"bond", node_name, shared_from_this());
238 bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
239 bond_map_[node_name]->setHeartbeatPeriod(0.10);
240 bond_map_[node_name]->start();
242 !bond_map_[node_name]->waitUntilFormed(
243 rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2))))
247 "Server %s was unable to be reached after %0.2fs by bond. "
248 "This server may be misconfigured.",
249 node_name.c_str(), timeout_s);
252 RCLCPP_INFO(get_logger(),
"Server %s connected with bond.", node_name.c_str());
261 message(transition_label_map_[transition] + node_name);
263 if (!node_map_[node_name]->change_state(transition, std::chrono::milliseconds(-1),
265 !(node_map_[node_name]->get_state(service_timeout_) == transition_state_map_[transition]))
267 RCLCPP_ERROR(get_logger(),
"Failed to change state for node: %s", node_name.c_str());
271 if (transition == Transition::TRANSITION_ACTIVATE) {
273 }
else if (transition == Transition::TRANSITION_DEACTIVATE) {
274 bond_map_.erase(node_name);
284 if (transition == Transition::TRANSITION_CONFIGURE ||
285 transition == Transition::TRANSITION_ACTIVATE)
287 for (
auto & node_name : node_names_) {
292 }
catch (
const std::runtime_error & e) {
295 "Failed to change state for node: %s. Exception: %s.", node_name.c_str(), e.what());
300 std::vector<std::string>::reverse_iterator rit;
301 for (rit = node_names_.rbegin(); rit != node_names_.rend(); ++rit) {
306 }
catch (
const std::runtime_error & e) {
309 "Failed to change state for node: %s. Exception: %s.", (*rit).c_str(), e.what());
320 message(
"Deactivate, cleanup, and shutdown nodes");
321 managed_nodes_state_ = NodeState::FINALIZED;
330 message(
"Starting managed nodes bringup...");
334 RCLCPP_ERROR(get_logger(),
"Failed to bring up all requested nodes. Aborting bringup.");
335 managed_nodes_state_ = NodeState::UNKNOWN;
338 message(
"Managed nodes are active");
339 managed_nodes_state_ = NodeState::ACTIVE;
347 message(
"Configuring managed nodes...");
349 RCLCPP_ERROR(get_logger(),
"Failed to configure all requested nodes. Aborting bringup.");
350 managed_nodes_state_ = NodeState::UNKNOWN;
353 message(
"Managed nodes are now configured");
354 managed_nodes_state_ = NodeState::INACTIVE;
361 message(
"Cleaning up managed nodes...");
363 RCLCPP_ERROR(get_logger(),
"Failed to cleanup all requested nodes. Aborting cleanup.");
364 managed_nodes_state_ = NodeState::UNKNOWN;
367 message(
"Managed nodes have been cleaned up");
368 managed_nodes_state_ = NodeState::UNCONFIGURED;
377 message(
"Shutting down managed nodes...");
380 message(
"Managed nodes have been shut down");
389 message(
"Resetting managed nodes...");
395 RCLCPP_ERROR(get_logger(),
"Failed to reset nodes: aborting reset");
396 managed_nodes_state_ = NodeState::UNKNOWN;
401 message(
"Managed nodes have been reset");
402 managed_nodes_state_ = NodeState::UNCONFIGURED;
411 message(
"Pausing managed nodes...");
413 RCLCPP_ERROR(get_logger(),
"Failed to pause nodes: aborting pause");
414 managed_nodes_state_ = NodeState::UNKNOWN;
418 message(
"Managed nodes have been paused");
419 managed_nodes_state_ = NodeState::INACTIVE;
426 message(
"Resuming managed nodes...");
428 RCLCPP_ERROR(get_logger(),
"Failed to resume nodes: aborting resume");
429 managed_nodes_state_ = NodeState::UNKNOWN;
433 message(
"Managed nodes are active");
434 managed_nodes_state_ = NodeState::ACTIVE;
442 if (bond_timeout_.count() <= 0) {
446 message(
"Creating bond timer...");
447 bond_timer_ = this->create_wall_timer(
457 message(
"Terminating bond timer...");
458 bond_timer_->cancel();
467 get_logger(),
"Running Nav2 LifecycleManager rcl preshutdown (%s)",
476 service_thread_.reset();
485 rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
487 context->add_pre_shutdown_callback(
495 if (!
isActive() || !rclcpp::ok() || bond_map_.empty()) {
499 for (
auto & node_name : node_names_) {
504 if (bond_map_[node_name]->isBroken()) {
507 "Have not received a heartbeat from " + node_name +
"."));
512 "CRITICAL FAILURE: SERVER %s IS DOWN after not receiving a heartbeat for %i ms."
513 " Shutting down related nodes.",
514 node_name.c_str(),
static_cast<int>(bond_timeout_.count()));
521 if (attempt_respawn_reconnection_) {
522 bond_respawn_timer_ = this->create_wall_timer(
536 if (bond_respawn_start_time_.nanoseconds() == 0) {
537 bond_respawn_start_time_ = now();
542 if (
isActive() || !rclcpp::ok() || node_names_.empty()) {
543 bond_respawn_start_time_ = rclcpp::Time(0);
544 bond_respawn_timer_.reset();
549 int live_servers = 0;
550 const int max_live_servers = node_names_.size();
551 for (
auto & node_name : node_names_) {
557 node_map_[node_name]->get_state(service_timeout_);
566 if (live_servers == max_live_servers) {
567 message(
"Successfully re-established connections from server respawns, starting back up.");
568 bond_respawn_start_time_ = rclcpp::Time(0);
569 bond_respawn_timer_.reset();
571 }
else if (now() - bond_respawn_start_time_ >= bond_respawn_max_duration_) {
572 message(
"Failed to re-establish connection from a server crash after maximum timeout.");
573 bond_respawn_start_time_ = rclcpp::Time(0);
574 bond_respawn_timer_.reset();
578 #define ANSI_COLOR_RESET "\x1b[0m"
579 #define ANSI_COLOR_BLUE "\x1b[34m"
584 RCLCPP_INFO(get_logger(), ANSI_COLOR_BLUE
"\33[1m%s\33[0m" ANSI_COLOR_RESET, msg.c_str());
589 #include "rclcpp_components/register_node_macro.hpp"
Implements service interface to transition the lifecycle nodes of Nav2 stack. It receives transition ...
void createBondTimer()
Support function for creating bond timer.
void destroyLifecycleServiceClients()
Destroy all the lifecycle service clients.
void destroyBondTimer()
Support function for killing bond connections.
bool cleanup()
Cleanups the managed nodes.
bool pause()
Pause all the managed nodes.
bool shutdown()
Deactivate, clean up and shut down all the managed nodes.
bool resume()
Resume all the managed nodes.
void createLifecycleServiceServers()
Support function for creating service servers.
void onRclPreshutdown()
Perform preshutdown activities before our Context is shutdown. Note that this is related to our Conte...
void checkBondConnections()
bool isActive()
function to check if managed nodes are active
bool createBondConnection(const std::string &node_name)
Support function for creating bond connections.
void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
function to check the state of Nav2 nodes
void registerRclPreshutdownCallback()
void message(const std::string &msg)
Helper function to highlight the output on the console.
~LifecycleManager()
A destructor for nav2_lifecycle_manager::LifecycleManager.
bool reset(bool hard_reset=false)
Reset all the managed nodes.
bool startup()
Start up managed nodes.
void shutdownAllNodes()
Support function for shutdown.
void checkBondRespawnConnection()
void managerCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< ManageLifecycleNodes::Request > request, std::shared_ptr< ManageLifecycleNodes::Response > response)
Lifecycle node manager callback function.
bool changeStateForNode(const std::string &node_name, std::uint8_t transition)
For a node, transition to the new target state.
bool configure()
Configures the managed nodes.
bool changeStateForAllNodes(std::uint8_t transition, bool hard_change=false)
For each node in the map, transition to the new target state.
void createLifecycleServiceClients()
Support function for creating service clients.
void isActiveCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< std_srvs::srv::Trigger::Request > request, std::shared_ptr< std_srvs::srv::Trigger::Response > response)
Trigger callback function checks if the managed nodes are in active state.
Helper functions to interact with a lifecycle node.