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();
93 init_timer_ = this->create_wall_timer(
96 init_timer_->cancel();
101 auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
102 executor->add_callback_group(callback_group_, get_node_base_interface());
103 service_thread_ = std::make_unique<nav2::NodeThread>(executor);
105 diagnostics_updater_.setHardwareID(
"Nav2");
111 RCLCPP_INFO(get_logger(),
"Destroying %s", get_name());
112 service_thread_.reset();
117 const std::shared_ptr<rmw_request_id_t>,
118 const std::shared_ptr<ManageLifecycleNodes::Request> request,
119 std::shared_ptr<ManageLifecycleNodes::Response> response)
121 switch (request->command) {
122 case ManageLifecycleNodes::Request::STARTUP:
125 case ManageLifecycleNodes::Request::CONFIGURE:
128 case ManageLifecycleNodes::Request::CLEANUP:
131 case ManageLifecycleNodes::Request::RESET:
132 response->success =
reset();
134 case ManageLifecycleNodes::Request::SHUTDOWN:
137 case ManageLifecycleNodes::Request::PAUSE:
138 response->success =
pause();
140 case ManageLifecycleNodes::Request::RESUME:
141 response->success =
resume();
149 managed_nodes_state_ = state;
156 return managed_nodes_state_ == NodeState::ACTIVE;
162 if (is_active_pub_ && is_active_pub_->is_activated()) {
163 auto message = std::make_unique<std_msgs::msg::Bool>();
165 is_active_pub_->publish(std::move(
message));
171 const std::shared_ptr<rmw_request_id_t>,
172 const std::shared_ptr<std_srvs::srv::Trigger::Request>,
173 std::shared_ptr<std_srvs::srv::Trigger::Response> response)
181 unsigned char error_level;
183 switch (managed_nodes_state_) {
184 case NodeState::ACTIVE:
185 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
186 message =
"Managed nodes are active";
188 case NodeState::INACTIVE:
189 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
190 message =
"Managed nodes are inactive";
192 case NodeState::UNCONFIGURED:
193 error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
194 message =
"Managed nodes are unconfigured";
196 case NodeState::FINALIZED:
197 error_level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
198 message =
"Managed nodes have been shut down";
201 error_level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
202 message =
"An error has occurred during a node state transition";
205 stat.summary(error_level,
message);
211 message(
"Creating and initializing lifecycle service clients");
212 for (
auto & node_name : node_names_) {
213 node_map_[node_name] =
214 std::make_shared<LifecycleServiceClient>(node_name, shared_from_this());
221 message(
"Creating and initializing lifecycle service servers");
225 manager_srv_ = nav2::interfaces::create_service<ManageLifecycleNodes>(
227 get_name() + std::string(
"/manage_nodes"),
231 is_active_srv_ = nav2::interfaces::create_service<std_srvs::srv::Trigger>(
233 get_name() + std::string(
"/is_active"),
241 message(
"Creating and initializing lifecycle publishers");
243 is_active_pub_ = nav2::interfaces::create_publisher<std_msgs::msg::Bool>(
245 get_name() + std::string(
"/managed_nodes_activated"),
248 is_active_pub_->on_activate();
256 message(
"Destroying lifecycle service clients");
257 for (
auto & kv : node_map_) {
265 message(
"Destroying lifecycle publishers");
266 if (is_active_pub_) {
267 is_active_pub_->on_deactivate();
268 is_active_pub_.reset();
275 const double timeout_ns =
276 std::chrono::duration_cast<std::chrono::nanoseconds>(bond_timeout_).count();
277 const double timeout_s = timeout_ns / 1e9;
279 if (bond_map_.find(node_name) == bond_map_.end() && bond_timeout_.count() > 0.0) {
280 bond_map_[node_name] =
281 std::make_shared<bond::Bond>(
"bond", node_name, shared_from_this());
282 bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
283 bond_map_[node_name]->setHeartbeatPeriod(0.10);
284 bond_map_[node_name]->start();
286 !bond_map_[node_name]->waitUntilFormed(
287 rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2))))
291 "Server %s was unable to be reached after %0.2fs by bond. "
292 "This server may be misconfigured.",
293 node_name.c_str(), timeout_s);
296 RCLCPP_INFO(get_logger(),
"Server %s connected with bond.", node_name.c_str());
305 message(transition_label_map_[transition] + node_name);
307 if (!node_map_[node_name]->change_state(transition, std::chrono::milliseconds(-1),
309 !(node_map_[node_name]->get_state(service_timeout_) == transition_state_map_[transition]))
311 RCLCPP_ERROR(get_logger(),
"Failed to change state for node: %s", node_name.c_str());
315 if (transition == Transition::TRANSITION_ACTIVATE) {
317 }
else if (transition == Transition::TRANSITION_DEACTIVATE) {
318 bond_map_.erase(node_name);
328 if (transition == Transition::TRANSITION_CONFIGURE ||
329 transition == Transition::TRANSITION_ACTIVATE)
331 for (
auto & node_name : node_names_) {
336 }
catch (
const std::runtime_error & e) {
339 "Failed to change state for node: %s. Exception: %s.", node_name.c_str(), e.what());
344 std::vector<std::string>::reverse_iterator rit;
345 for (rit = node_names_.rbegin(); rit != node_names_.rend(); ++rit) {
350 }
catch (
const std::runtime_error & e) {
353 "Failed to change state for node: %s. Exception: %s.", (*rit).c_str(), e.what());
364 message(
"Deactivate, cleanup, and shutdown nodes");
374 message(
"Starting managed nodes bringup...");
378 RCLCPP_ERROR(get_logger(),
"Failed to bring up all requested nodes. Aborting bringup.");
382 message(
"Managed nodes are active");
391 message(
"Configuring managed nodes...");
393 RCLCPP_ERROR(get_logger(),
"Failed to configure all requested nodes. Aborting bringup.");
397 message(
"Managed nodes are now configured");
405 message(
"Cleaning up managed nodes...");
407 RCLCPP_ERROR(get_logger(),
"Failed to cleanup all requested nodes. Aborting cleanup.");
411 message(
"Managed nodes have been cleaned up");
421 message(
"Shutting down managed nodes...");
425 message(
"Managed nodes have been shut down");
434 message(
"Resetting managed nodes...");
440 RCLCPP_ERROR(get_logger(),
"Failed to reset nodes: aborting reset");
446 message(
"Managed nodes have been reset");
456 message(
"Pausing managed nodes...");
458 RCLCPP_ERROR(get_logger(),
"Failed to pause nodes: aborting pause");
463 message(
"Managed nodes have been paused");
471 message(
"Resuming managed nodes...");
473 RCLCPP_ERROR(get_logger(),
"Failed to resume nodes: aborting resume");
478 message(
"Managed nodes are active");
487 if (bond_timeout_.count() <= 0) {
491 message(
"Creating bond timer...");
492 bond_timer_ = this->create_wall_timer(
502 message(
"Terminating bond timer...");
503 bond_timer_->cancel();
512 get_logger(),
"Running Nav2 LifecycleManager rcl preshutdown (%s)",
521 service_thread_.reset();
530 rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context();
532 context->add_pre_shutdown_callback(
540 if (!
isActive() || !rclcpp::ok() || bond_map_.empty()) {
544 for (
auto & node_name : node_names_) {
549 if (bond_map_[node_name]->isBroken()) {
552 "Have not received a heartbeat from " + node_name +
"."));
557 "CRITICAL FAILURE: SERVER %s IS DOWN after not receiving a heartbeat for %i ms."
558 " Shutting down related nodes.",
559 node_name.c_str(),
static_cast<int>(bond_timeout_.count()));
566 if (attempt_respawn_reconnection_) {
567 bond_respawn_timer_ = this->create_wall_timer(
581 if (bond_respawn_start_time_.nanoseconds() == 0) {
582 bond_respawn_start_time_ = now();
587 if (
isActive() || !rclcpp::ok() || node_names_.empty()) {
588 bond_respawn_start_time_ = rclcpp::Time(0);
589 bond_respawn_timer_.reset();
594 int live_servers = 0;
595 const int max_live_servers = node_names_.size();
596 for (
auto & node_name : node_names_) {
602 node_map_[node_name]->get_state(service_timeout_);
611 if (live_servers == max_live_servers) {
612 message(
"Successfully re-established connections from server respawns, starting back up.");
613 bond_respawn_start_time_ = rclcpp::Time(0);
614 bond_respawn_timer_.reset();
616 }
else if (now() - bond_respawn_start_time_ >= bond_respawn_max_duration_) {
617 message(
"Failed to re-establish connection from a server crash after maximum timeout.");
618 bond_respawn_start_time_ = rclcpp::Time(0);
619 bond_respawn_timer_.reset();
623 #define ANSI_COLOR_RESET "\x1b[0m"
624 #define ANSI_COLOR_BLUE "\x1b[34m"
629 RCLCPP_INFO(get_logger(), ANSI_COLOR_BLUE
"\33[1m%s\33[0m" ANSI_COLOR_RESET, msg.c_str());
634 #include "rclcpp_components/register_node_macro.hpp"
A QoS profile for latched, reliable topics with a history of 1 messages.
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()
void destroyLifecyclePublishers()
Destroy all the lifecycle publishers.
bool isActive()
function to check if managed nodes are active
bool createBondConnection(const std::string &node_name)
Support function for creating bond connections.
void createLifecyclePublishers()
Support function for creating publishers.
void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
function to check the state of Nav2 nodes
void publishIsActiveState()
Publish the is_active state.
void registerRclPreshutdownCallback()
void message(const std::string &msg)
Helper function to highlight the output on the console.
void setState(const NodeState &state)
Set the state of managed nodes.
~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.