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(
"bond_respawn_max_duration", 10.0);
46 declare_parameter(
"attempt_respawn_reconnection",
true);
50 node_names_ = get_parameter(
"node_names").as_string_array();
51 get_parameter(
"autostart", autostart_);
52 double bond_timeout_s;
53 get_parameter(
"bond_timeout", bond_timeout_s);
54 bond_timeout_ = std::chrono::duration_cast<std::chrono::milliseconds>(
55 std::chrono::duration<double>(bond_timeout_s));
57 double respawn_timeout_s;
58 get_parameter(
"bond_respawn_max_duration", respawn_timeout_s);
59 bond_respawn_max_duration_ = rclcpp::Duration::from_seconds(respawn_timeout_s);
61 get_parameter(
"attempt_respawn_reconnection", attempt_respawn_reconnection_);
63 callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive,
false);
64 manager_srv_ = create_service<ManageLifecycleNodes>(
65 get_name() + std::string(
"/manage_nodes"),
67 rclcpp::SystemDefaultsQoS(),
70 is_active_srv_ = create_service<std_srvs::srv::Trigger>(
71 get_name() + std::string(
"/is_active"),
73 rclcpp::SystemDefaultsQoS(),
76 transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
77 transition_state_map_[Transition::TRANSITION_CLEANUP] = State::PRIMARY_STATE_UNCONFIGURED;
78 transition_state_map_[Transition::TRANSITION_ACTIVATE] = State::PRIMARY_STATE_ACTIVE;
79 transition_state_map_[Transition::TRANSITION_DEACTIVATE] = State::PRIMARY_STATE_INACTIVE;
80 transition_state_map_[Transition::TRANSITION_UNCONFIGURED_SHUTDOWN] =
81 State::PRIMARY_STATE_FINALIZED;
83 transition_label_map_[Transition::TRANSITION_CONFIGURE] = std::string(
"Configuring ");
84 transition_label_map_[Transition::TRANSITION_CLEANUP] = std::string(
"Cleaning up ");
85 transition_label_map_[Transition::TRANSITION_ACTIVATE] = std::string(
"Activating ");
86 transition_label_map_[Transition::TRANSITION_DEACTIVATE] = std::string(
"Deactivating ");
87 transition_label_map_[Transition::TRANSITION_UNCONFIGURED_SHUTDOWN] =
88 std::string(
"Shutting down ");
90 init_timer_ = this->create_wall_timer(
93 init_timer_->cancel();
96 init_timer_ = this->create_wall_timer(
99 init_timer_->cancel();
104 auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
105 executor->add_callback_group(callback_group_, get_node_base_interface());
106 service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
108 diagnostics_updater_.setHardwareID(
"Nav2");
114 RCLCPP_INFO(get_logger(),
"Destroying %s", get_name());
115 service_thread_.reset();
120 const std::shared_ptr<rmw_request_id_t>,
121 const std::shared_ptr<ManageLifecycleNodes::Request> request,
122 std::shared_ptr<ManageLifecycleNodes::Response> response)
124 switch (request->command) {
125 case ManageLifecycleNodes::Request::STARTUP:
128 case ManageLifecycleNodes::Request::CONFIGURE:
131 case ManageLifecycleNodes::Request::CLEANUP:
134 case ManageLifecycleNodes::Request::RESET:
135 response->success =
reset();
137 case ManageLifecycleNodes::Request::SHUTDOWN:
140 case ManageLifecycleNodes::Request::PAUSE:
141 response->success =
pause();
143 case ManageLifecycleNodes::Request::RESUME:
144 response->success =
resume();
152 return managed_nodes_state_ == NodeState::ACTIVE;
157 const std::shared_ptr<rmw_request_id_t>,
158 const std::shared_ptr<std_srvs::srv::Trigger::Request>,
159 std::shared_ptr<std_srvs::srv::Trigger::Response> response)
167 unsigned char error_level;
169 switch (managed_nodes_state_) {
170 case NodeState::ACTIVE:
171 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
172 message =
"Managed nodes are active";
174 case NodeState::INACTIVE:
175 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
176 message =
"Managed nodes are inactive";
178 case NodeState::UNCONFIGURED:
179 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
180 message =
"Managed nodes are unconfigured";
182 case NodeState::FINALIZED:
183 error_level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
184 message =
"Managed nodes have been shut down";
187 error_level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
188 message =
"An error has occurred during a node state transition";
191 stat.summary(error_level,
message);
197 message(
"Creating and initializing lifecycle service clients");
198 for (
auto & node_name : node_names_) {
199 node_map_[node_name] =
200 std::make_shared<LifecycleServiceClient>(node_name, shared_from_this());
207 message(
"Destroying lifecycle service clients");
208 for (
auto & kv : node_map_) {
216 const double timeout_ns =
217 std::chrono::duration_cast<std::chrono::nanoseconds>(bond_timeout_).count();
218 const double timeout_s = timeout_ns / 1e9;
220 if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) {
221 bond_map_[node_name] =
222 std::make_shared<bond::Bond>(
"bond", node_name, shared_from_this());
223 bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
224 bond_map_[node_name]->setHeartbeatPeriod(0.10);
225 bond_map_[node_name]->start();
227 !bond_map_[node_name]->waitUntilFormed(
228 rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2))))
232 "Server %s was unable to be reached after %0.2fs by bond. "
233 "This server may be misconfigured.",
234 node_name.c_str(), timeout_s);
237 RCLCPP_INFO(get_logger(),
"Server %s connected with bond.", node_name.c_str());
246 message(transition_label_map_[transition] + node_name);
248 if (!node_map_[node_name]->change_state(transition) ||
249 !(node_map_[node_name]->get_state() == transition_state_map_[transition]))
251 RCLCPP_ERROR(get_logger(),
"Failed to change state for node: %s", node_name.c_str());
255 if (transition == Transition::TRANSITION_ACTIVATE) {
257 }
else if (transition == Transition::TRANSITION_DEACTIVATE) {
258 bond_map_.erase(node_name);
268 if (transition == Transition::TRANSITION_CONFIGURE ||
269 transition == Transition::TRANSITION_ACTIVATE)
271 for (
auto & node_name : node_names_) {
276 }
catch (
const std::runtime_error & e) {
279 "Failed to change state for node: %s. Exception: %s.", node_name.c_str(), e.what());
284 std::vector<std::string>::reverse_iterator rit;
285 for (rit = node_names_.rbegin(); rit != node_names_.rend(); ++rit) {
290 }
catch (
const std::runtime_error & e) {
293 "Failed to change state for node: %s. Exception: %s.", (*rit).c_str(), e.what());
304 message(
"Deactivate, cleanup, and shutdown nodes");
305 managed_nodes_state_ = NodeState::FINALIZED;
314 message(
"Starting managed nodes bringup...");
318 RCLCPP_ERROR(get_logger(),
"Failed to bring up all requested nodes. Aborting bringup.");
319 managed_nodes_state_ = NodeState::UNKNOWN;
322 message(
"Managed nodes are active");
323 managed_nodes_state_ = NodeState::ACTIVE;
331 message(
"Configuring managed nodes...");
333 RCLCPP_ERROR(get_logger(),
"Failed to configure all requested nodes. Aborting bringup.");
334 managed_nodes_state_ = NodeState::UNKNOWN;
337 message(
"Managed nodes are now configured");
338 managed_nodes_state_ = NodeState::INACTIVE;
345 message(
"Cleaning up managed nodes...");
347 RCLCPP_ERROR(get_logger(),
"Failed to cleanup all requested nodes. Aborting cleanup.");
348 managed_nodes_state_ = NodeState::UNKNOWN;
351 message(
"Managed nodes have been cleaned up");
352 managed_nodes_state_ = NodeState::UNCONFIGURED;
361 message(
"Shutting down managed nodes...");
364 message(
"Managed nodes have been shut down");
373 message(
"Resetting managed nodes...");
379 RCLCPP_ERROR(get_logger(),
"Failed to reset nodes: aborting reset");
380 managed_nodes_state_ = NodeState::UNKNOWN;
385 message(
"Managed nodes have been reset");
386 managed_nodes_state_ = NodeState::UNCONFIGURED;
395 message(
"Pausing managed nodes...");
397 RCLCPP_ERROR(get_logger(),
"Failed to pause nodes: aborting pause");
398 managed_nodes_state_ = NodeState::UNKNOWN;
402 message(
"Managed nodes have been paused");
403 managed_nodes_state_ = NodeState::INACTIVE;
410 message(
"Resuming managed nodes...");
412 RCLCPP_ERROR(get_logger(),
"Failed to resume nodes: aborting resume");
413 managed_nodes_state_ = NodeState::UNKNOWN;
417 message(
"Managed nodes are active");
418 managed_nodes_state_ = NodeState::ACTIVE;
426 if (bond_timeout_.count() <= 0) {
430 message(
"Creating bond timer...");
431 bond_timer_ = this->create_wall_timer(
441 message(
"Terminating bond timer...");
442 bond_timer_->cancel();
451 get_logger(),
"Running Nav2 LifecycleManager rcl preshutdown (%s)",
460 service_thread_.reset();
469 rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
471 context->add_pre_shutdown_callback(
479 if (!
isActive() || !rclcpp::ok() || bond_map_.empty()) {
483 for (
auto & node_name : node_names_) {
488 if (bond_map_[node_name]->isBroken()) {
491 "Have not received a heartbeat from " + node_name +
"."));
496 "CRITICAL FAILURE: SERVER %s IS DOWN after not receiving a heartbeat for %i ms."
497 " Shutting down related nodes.",
498 node_name.c_str(),
static_cast<int>(bond_timeout_.count()));
505 if (attempt_respawn_reconnection_) {
506 bond_respawn_timer_ = this->create_wall_timer(
520 if (bond_respawn_start_time_.nanoseconds() == 0) {
521 bond_respawn_start_time_ = now();
526 if (
isActive() || !rclcpp::ok() || node_names_.empty()) {
527 bond_respawn_start_time_ = rclcpp::Time(0);
528 bond_respawn_timer_.reset();
533 int live_servers = 0;
534 const int max_live_servers = node_names_.size();
535 for (
auto & node_name : node_names_) {
541 node_map_[node_name]->get_state();
550 if (live_servers == max_live_servers) {
551 message(
"Successfully re-established connections from server respawns, starting back up.");
552 bond_respawn_start_time_ = rclcpp::Time(0);
553 bond_respawn_timer_.reset();
555 }
else if (now() - bond_respawn_start_time_ >= bond_respawn_max_duration_) {
556 message(
"Failed to re-establish connection from a server crash after maximum timeout.");
557 bond_respawn_start_time_ = rclcpp::Time(0);
558 bond_respawn_timer_.reset();
562 #define ANSI_COLOR_RESET "\x1b[0m"
563 #define ANSI_COLOR_BLUE "\x1b[34m"
568 RCLCPP_INFO(get_logger(), ANSI_COLOR_BLUE
"\33[1m%s\33[0m" ANSI_COLOR_RESET, msg.c_str());
573 #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 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.