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::ServicesQoS().get_rmw_qos_profile(),
70 is_active_srv_ = create_service<std_srvs::srv::Trigger>(
71 get_name() + std::string(
"/is_active"),
73 rclcpp::ServicesQoS().get_rmw_qos_profile(),
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::RESET:
129 response->success =
reset();
131 case ManageLifecycleNodes::Request::SHUTDOWN:
134 case ManageLifecycleNodes::Request::PAUSE:
135 response->success =
pause();
137 case ManageLifecycleNodes::Request::RESUME:
138 response->success =
resume();
145 const std::shared_ptr<rmw_request_id_t>,
146 const std::shared_ptr<std_srvs::srv::Trigger::Request>,
147 std::shared_ptr<std_srvs::srv::Trigger::Response> response)
149 response->success = system_active_;
155 if (system_active_) {
156 stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK,
"Nav2 is active");
158 stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR,
"Nav2 is inactive");
165 message(
"Creating and initializing lifecycle service clients");
166 for (
auto & node_name : node_names_) {
167 node_map_[node_name] =
168 std::make_shared<LifecycleServiceClient>(node_name, shared_from_this());
175 message(
"Destroying lifecycle service clients");
176 for (
auto & kv : node_map_) {
184 const double timeout_ns =
185 std::chrono::duration_cast<std::chrono::nanoseconds>(bond_timeout_).count();
186 const double timeout_s = timeout_ns / 1e9;
188 if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) {
189 bond_map_[node_name] =
190 std::make_shared<bond::Bond>(
"bond", node_name, shared_from_this());
191 bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
192 bond_map_[node_name]->setHeartbeatPeriod(0.10);
193 bond_map_[node_name]->start();
195 !bond_map_[node_name]->waitUntilFormed(
196 rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2))))
200 "Server %s was unable to be reached after %0.2fs by bond. "
201 "This server may be misconfigured.",
202 node_name.c_str(), timeout_s);
205 RCLCPP_INFO(get_logger(),
"Server %s connected with bond.", node_name.c_str());
214 message(transition_label_map_[transition] + node_name);
216 if (!node_map_[node_name]->change_state(transition) ||
217 !(node_map_[node_name]->get_state() == transition_state_map_[transition]))
219 RCLCPP_ERROR(get_logger(),
"Failed to change state for node: %s", node_name.c_str());
223 if (transition == Transition::TRANSITION_ACTIVATE) {
225 }
else if (transition == Transition::TRANSITION_DEACTIVATE) {
226 bond_map_.erase(node_name);
236 if (transition == Transition::TRANSITION_CONFIGURE ||
237 transition == Transition::TRANSITION_ACTIVATE)
239 for (
auto & node_name : node_names_) {
244 }
catch (
const std::runtime_error & e) {
247 "Failed to change state for node: %s. Exception: %s.", node_name.c_str(), e.what());
252 std::vector<std::string>::reverse_iterator rit;
253 for (rit = node_names_.rbegin(); rit != node_names_.rend(); ++rit) {
258 }
catch (
const std::runtime_error & e) {
261 "Failed to change state for node: %s. Exception: %s.", (*rit).c_str(), e.what());
272 message(
"Deactivate, cleanup, and shutdown nodes");
281 message(
"Starting managed nodes bringup...");
285 RCLCPP_ERROR(get_logger(),
"Failed to bring up all requested nodes. Aborting bringup.");
288 message(
"Managed nodes are active");
289 system_active_ =
true;
297 system_active_ =
false;
300 message(
"Shutting down managed nodes...");
303 message(
"Managed nodes have been shut down");
310 system_active_ =
false;
313 message(
"Resetting managed nodes...");
319 RCLCPP_ERROR(get_logger(),
"Failed to reset nodes: aborting reset");
324 message(
"Managed nodes have been reset");
331 system_active_ =
false;
334 message(
"Pausing managed nodes...");
336 RCLCPP_ERROR(get_logger(),
"Failed to pause nodes: aborting pause");
340 message(
"Managed nodes have been paused");
347 message(
"Resuming managed nodes...");
349 RCLCPP_ERROR(get_logger(),
"Failed to resume nodes: aborting resume");
353 message(
"Managed nodes are active");
354 system_active_ =
true;
362 if (bond_timeout_.count() <= 0) {
366 message(
"Creating bond timer...");
367 bond_timer_ = this->create_wall_timer(
377 message(
"Terminating bond timer...");
378 bond_timer_->cancel();
387 get_logger(),
"Running Nav2 LifecycleManager rcl preshutdown (%s)",
396 service_thread_.reset();
405 rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
407 context->add_pre_shutdown_callback(
415 if (!system_active_ || !rclcpp::ok() || bond_map_.empty()) {
419 for (
auto & node_name : node_names_) {
424 if (bond_map_[node_name]->isBroken()) {
427 "Have not received a heartbeat from " + node_name +
"."));
432 "CRITICAL FAILURE: SERVER %s IS DOWN after not receiving a heartbeat for %i ms."
433 " Shutting down related nodes.",
434 node_name.c_str(),
static_cast<int>(bond_timeout_.count()));
441 if (attempt_respawn_reconnection_) {
442 bond_respawn_timer_ = this->create_wall_timer(
456 if (bond_respawn_start_time_.nanoseconds() == 0) {
457 bond_respawn_start_time_ = now();
462 if (system_active_ || !rclcpp::ok() || node_names_.empty()) {
463 bond_respawn_start_time_ = rclcpp::Time(0);
464 bond_respawn_timer_.reset();
469 int live_servers = 0;
470 const int max_live_servers = node_names_.size();
471 for (
auto & node_name : node_names_) {
477 node_map_[node_name]->get_state();
486 if (live_servers == max_live_servers) {
487 message(
"Successfully re-established connections from server respawns, starting back up.");
488 bond_respawn_start_time_ = rclcpp::Time(0);
489 bond_respawn_timer_.reset();
491 }
else if (now() - bond_respawn_start_time_ >= bond_respawn_max_duration_) {
492 message(
"Failed to re-establish connection from a server crash after maximum timeout.");
493 bond_respawn_start_time_ = rclcpp::Time(0);
494 bond_respawn_timer_.reset();
498 #define ANSI_COLOR_RESET "\x1b[0m"
499 #define ANSI_COLOR_BLUE "\x1b[34m"
504 RCLCPP_INFO(get_logger(), ANSI_COLOR_BLUE
"\33[1m%s\33[0m" ANSI_COLOR_RESET, msg.c_str());
509 #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 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 CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
function to check if the Nav2 system is active
void checkBondConnections()
bool createBondConnection(const std::string &node_name)
Support function for creating bond connections.
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 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.