Skip to content

Commit 57dd8d4

Browse files
PlaqueoffPekka Myller
andauthored
Stop error diagnostics when pausing nav (ros-navigation#3830)
* Added nodestate enum and a variable to keep track of current state of managed nodes. * Updating state_of_managed_nodes_ when switching states and using it to determine an accurate diagnostics message. * Fixing bugs. * Updated/added docstrings. * Publishing OK status when nodes are unconfigured. Changed if-else chain to switch case. * Renamed NodeState PAUSED to INACTIVE, state_of_managed_nodes_ to managed_nodes_state_ and replaced system_active_ with an inline method. * Bugfix. --------- Co-authored-by: Pekka Myller <pekka.myller@karelics.fi>
1 parent 4ce7702 commit 57dd8d4

File tree

2 files changed

+64
-18
lines changed

2 files changed

+64
-18
lines changed

nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,17 @@ namespace nav2_lifecycle_manager
3838
using namespace std::chrono_literals; // NOLINT
3939

4040
using nav2_msgs::srv::ManageLifecycleNodes;
41+
42+
/// @brief Enum to for keeping track of the state of managed nodes
43+
enum NodeState
44+
{
45+
UNCONFIGURED,
46+
ACTIVE,
47+
INACTIVE,
48+
FINALIZED,
49+
UNKNOWN,
50+
};
51+
4152
/**
4253
* @class nav2_lifecycle_manager::LifecycleManager
4354
* @brief Implements service interface to transition the lifecycle nodes of
@@ -189,9 +200,9 @@ class LifecycleManager : public rclcpp::Node
189200

190201
// Diagnostics functions
191202
/**
192-
* @brief function to check if the Nav2 system is active
203+
* @brief function to check the state of Nav2 nodes
193204
*/
194-
void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
205+
void CreateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);
195206

196207
/**
197208
* Register our preshutdown callback for this Node's rcl Context.
@@ -201,6 +212,11 @@ class LifecycleManager : public rclcpp::Node
201212
*/
202213
void registerRclPreshutdownCallback();
203214

215+
/**
216+
* @brief function to check if managed nodes are active
217+
*/
218+
bool isActive();
219+
204220
// Timer thread to look at bond connections
205221
rclcpp::TimerBase::SharedPtr init_timer_;
206222
rclcpp::TimerBase::SharedPtr bond_timer_;
@@ -225,7 +241,7 @@ class LifecycleManager : public rclcpp::Node
225241
bool autostart_;
226242
bool attempt_respawn_reconnection_;
227243

228-
bool system_active_{false};
244+
NodeState managed_nodes_state_{NodeState::UNCONFIGURED};
229245
diagnostic_updater::Updater diagnostics_updater_;
230246

231247
rclcpp::Time bond_respawn_start_time_{0};

nav2_lifecycle_manager/src/lifecycle_manager.cpp

Lines changed: 45 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -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

112112
LifecycleManager::~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+
143149
void
144150
LifecycleManager::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

152158
void
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

162188
void
@@ -270,6 +296,7 @@ void
270296
LifecycleManager::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

294322
bool
295323
LifecycleManager::shutdown()
296324
{
297-
system_active_ = false;
298325
destroyBondTimer();
299326

300327
message("Shutting down managed nodes...");
@@ -307,7 +334,6 @@ LifecycleManager::shutdown()
307334
bool
308335
LifecycleManager::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

328356
bool
329357
LifecycleManager::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()
412442
void
413443
LifecycleManager::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

Comments
 (0)