@@ -106,7 +106,7 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
106106 service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
107107 });
108108 diagnostics_updater_.setHardwareID (" Nav2" );
109- diagnostics_updater_.add (" Nav2 Health" , this , &LifecycleManager::CreateActiveDiagnostic );
109+ diagnostics_updater_.add (" Nav2 Health" , this , &LifecycleManager::CreateDiagnostic );
110110}
111111
112112LifecycleManager::~LifecycleManager ()
@@ -140,23 +140,49 @@ LifecycleManager::managerCallback(
140140 }
141141}
142142
143+ inline bool
144+ LifecycleManager::isActive ()
145+ {
146+ return managed_nodes_state_ == NodeState::ACTIVE;
147+ }
148+
143149void
144150LifecycleManager::isActiveCallback (
145151 const std::shared_ptr<rmw_request_id_t >/* request_header*/ ,
146152 const std::shared_ptr<std_srvs::srv::Trigger::Request>/* request*/ ,
147153 std::shared_ptr<std_srvs::srv::Trigger::Response> response)
148154{
149- response->success = system_active_ ;
155+ response->success = isActive () ;
150156}
151157
152158void
153- LifecycleManager::CreateActiveDiagnostic (diagnostic_updater::DiagnosticStatusWrapper & stat)
159+ LifecycleManager::CreateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper & stat)
154160{
155- if (system_active_) {
156- stat.summary (diagnostic_msgs::msg::DiagnosticStatus::OK, " Nav2 is active" );
157- } else {
158- stat.summary (diagnostic_msgs::msg::DiagnosticStatus::ERROR, " Nav2 is inactive" );
161+ unsigned char error_level;
162+ std::string message;
163+ switch (managed_nodes_state_) {
164+ case NodeState::ACTIVE:
165+ error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
166+ message = " Managed nodes are active" ;
167+ break ;
168+ case NodeState::INACTIVE:
169+ error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
170+ message = " Managed nodes are inactive" ;
171+ break ;
172+ case NodeState::UNCONFIGURED:
173+ error_level = diagnostic_msgs::msg::DiagnosticStatus::OK;
174+ message = " Managed nodes are unconfigured" ;
175+ break ;
176+ case NodeState::FINALIZED:
177+ error_level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
178+ message = " Managed nodes have been shut down" ;
179+ break ;
180+ case NodeState::UNKNOWN:
181+ error_level = diagnostic_msgs::msg::DiagnosticStatus::ERROR;
182+ message = " An error has occurred during a node state transition" ;
183+ break ;
159184 }
185+ stat.summary (error_level, message);
160186}
161187
162188void
270296LifecycleManager::shutdownAllNodes ()
271297{
272298 message (" Deactivate, cleanup, and shutdown nodes" );
299+ managed_nodes_state_ = NodeState::FINALIZED;
273300 changeStateForAllNodes (Transition::TRANSITION_DEACTIVATE);
274301 changeStateForAllNodes (Transition::TRANSITION_CLEANUP);
275302 changeStateForAllNodes (Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
@@ -283,18 +310,18 @@ LifecycleManager::startup()
283310 !changeStateForAllNodes (Transition::TRANSITION_ACTIVATE))
284311 {
285312 RCLCPP_ERROR (get_logger (), " Failed to bring up all requested nodes. Aborting bringup." );
313+ managed_nodes_state_ = NodeState::UNKNOWN;
286314 return false ;
287315 }
288316 message (" Managed nodes are active" );
289- system_active_ = true ;
317+ managed_nodes_state_ = NodeState::ACTIVE ;
290318 createBondTimer ();
291319 return true ;
292320}
293321
294322bool
295323LifecycleManager::shutdown ()
296324{
297- system_active_ = false ;
298325 destroyBondTimer ();
299326
300327 message (" Shutting down managed nodes..." );
@@ -307,7 +334,6 @@ LifecycleManager::shutdown()
307334bool
308335LifecycleManager::reset (bool hard_reset)
309336{
310- system_active_ = false ;
311337 destroyBondTimer ();
312338
313339 message (" Resetting managed nodes..." );
@@ -317,27 +343,30 @@ LifecycleManager::reset(bool hard_reset)
317343 {
318344 if (!hard_reset) {
319345 RCLCPP_ERROR (get_logger (), " Failed to reset nodes: aborting reset" );
346+ managed_nodes_state_ = NodeState::UNKNOWN;
320347 return false ;
321348 }
322349 }
323350
324351 message (" Managed nodes have been reset" );
352+ managed_nodes_state_ = NodeState::UNCONFIGURED;
325353 return true ;
326354}
327355
328356bool
329357LifecycleManager::pause ()
330358{
331- system_active_ = false ;
332359 destroyBondTimer ();
333360
334361 message (" Pausing managed nodes..." );
335362 if (!changeStateForAllNodes (Transition::TRANSITION_DEACTIVATE)) {
336363 RCLCPP_ERROR (get_logger (), " Failed to pause nodes: aborting pause" );
364+ managed_nodes_state_ = NodeState::UNKNOWN;
337365 return false ;
338366 }
339367
340368 message (" Managed nodes have been paused" );
369+ managed_nodes_state_ = NodeState::INACTIVE;
341370 return true ;
342371}
343372
@@ -347,11 +376,12 @@ LifecycleManager::resume()
347376 message (" Resuming managed nodes..." );
348377 if (!changeStateForAllNodes (Transition::TRANSITION_ACTIVATE)) {
349378 RCLCPP_ERROR (get_logger (), " Failed to resume nodes: aborting resume" );
379+ managed_nodes_state_ = NodeState::UNKNOWN;
350380 return false ;
351381 }
352382
353383 message (" Managed nodes are active" );
354- system_active_ = true ;
384+ managed_nodes_state_ = NodeState::ACTIVE ;
355385 createBondTimer ();
356386 return true ;
357387}
@@ -412,7 +442,7 @@ LifecycleManager::registerRclPreshutdownCallback()
412442void
413443LifecycleManager::checkBondConnections ()
414444{
415- if (!system_active_ || !rclcpp::ok () || bond_map_.empty ()) {
445+ if (!isActive () || !rclcpp::ok () || bond_map_.empty ()) {
416446 return ;
417447 }
418448
@@ -457,9 +487,9 @@ LifecycleManager::checkBondRespawnConnection()
457487 bond_respawn_start_time_ = now ();
458488 }
459489
460- // Note: system_active_ is inverted since this should be in a failure
490+ // Note: isActive() is inverted since this should be in a failure
461491 // condition. If another outside user actives the system again, this should not process.
462- if (system_active_ || !rclcpp::ok () || node_names_.empty ()) {
492+ if (isActive () || !rclcpp::ok () || node_names_.empty ()) {
463493 bond_respawn_start_time_ = rclcpp::Time (0 );
464494 bond_respawn_timer_.reset ();
465495 return ;
0 commit comments