From 8b9a75afbfaa5d4fa9bc1bf09bf72a85f06f4b64 Mon Sep 17 00:00:00 2001 From: Ferry Schoenmakers Date: Thu, 1 Feb 2024 10:58:13 +0100 Subject: [PATCH 1/2] Port back feature from nobleo-noetic-devel where we also report the message that made stuff go bad --- diagnostic_aggregator/src/aggregator.cpp | 32 ++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/diagnostic_aggregator/src/aggregator.cpp b/diagnostic_aggregator/src/aggregator.cpp index 6b60eee3..2f10c7cd 100644 --- a/diagnostic_aggregator/src/aggregator.cpp +++ b/diagnostic_aggregator/src/aggregator.cpp @@ -217,6 +217,8 @@ void Aggregator::publishData() diag_toplevel_state.level = DiagnosticStatus::STALE; int max_level = -1; int min_level = 255; + int non_ok_status_depth = 0; + std::shared_ptr msg_to_report; std::vector> processed; { @@ -225,27 +227,57 @@ void Aggregator::publishData() } for (const auto & msg : processed) { diag_array.status.push_back(*msg); + const auto depth = std::count(msg->name.begin(), msg->name.end(), '/'); if (msg->level > max_level) { max_level = msg->level; + non_ok_status_depth = depth; + msg_to_report = msg; + } + if (msg->level == max_level && depth > non_ok_status_depth) { + // On non okay diagnostics also copy the deepest message to toplevel state + non_ok_status_depth = depth; + msg_to_report = msg; } if (msg->level < min_level) { min_level = msg->level; } } + // When a non-ok item was found, copy the complete status message once + if (max_level > DiagnosticStatus::OK) { + diag_toplevel_state.name = msg_to_report->name; + diag_toplevel_state.message = msg_to_report->message; + diag_toplevel_state.hardware_id = msg_to_report->hardware_id; + diag_toplevel_state.values = msg_to_report->values; + } std::vector> processed_other = other_analyzer_->report(); for (const auto & msg : processed_other) { diag_array.status.push_back(*msg); + const auto depth = std::count(msg->name.begin(), msg->name.end(), '/'); if (msg->level > max_level) { max_level = msg->level; + non_ok_status_depth = depth; + msg_to_report = msg; + } + if (msg->level == max_level && depth > non_ok_status_depth) { + // On non okay diagnostics also copy the deepest message to toplevel state + non_ok_status_depth = depth; + msg_to_report = msg; } if (msg->level < min_level) { min_level = msg->level; } } + // When a non-ok item was found, copy the complete status message once + if (max_level > DiagnosticStatus::OK) { + diag_toplevel_state.name = msg_to_report->name; + diag_toplevel_state.message = msg_to_report->message; + diag_toplevel_state.hardware_id = msg_to_report->hardware_id; + diag_toplevel_state.values = msg_to_report->values; + } diag_array.header.stamp = clock_->now(); agg_pub_->publish(diag_array); From 601b4a6d8b29d13396db074a15baac0d1f37b9ad Mon Sep 17 00:00:00 2001 From: Ferry Schoenmakers Date: Mon, 29 Apr 2024 13:51:41 +0200 Subject: [PATCH 2/2] ROS2 port of feature to report stale when no errors but stale items --- diagnostic_aggregator/src/aggregator.cpp | 31 ++++++++++++------- diagnostic_aggregator/src/analyzer_group.cpp | 18 +++++++---- .../test/test_discard_behavior.py | 4 +-- 3 files changed, 34 insertions(+), 19 deletions(-) diff --git a/diagnostic_aggregator/src/aggregator.cpp b/diagnostic_aggregator/src/aggregator.cpp index 2f10c7cd..4952b735 100644 --- a/diagnostic_aggregator/src/aggregator.cpp +++ b/diagnostic_aggregator/src/aggregator.cpp @@ -216,7 +216,7 @@ void Aggregator::publishData() diag_toplevel_state.name = "toplevel_state"; diag_toplevel_state.level = DiagnosticStatus::STALE; int max_level = -1; - int min_level = 255; + int8_t max_level_without_stale = 0; int non_ok_status_depth = 0; std::shared_ptr msg_to_report; @@ -239,8 +239,11 @@ void Aggregator::publishData() non_ok_status_depth = depth; msg_to_report = msg; } - if (msg->level < min_level) { - min_level = msg->level; + if ( + msg->level > max_level_without_stale && + msg->level != diagnostic_msgs::msg::DiagnosticStatus::STALE) + { + max_level_without_stale = msg->level; } } // When a non-ok item was found, copy the complete status message once @@ -251,6 +254,7 @@ void Aggregator::publishData() diag_toplevel_state.values = msg_to_report->values; } + non_ok_status_depth = 0; std::vector> processed_other = other_analyzer_->report(); for (const auto & msg : processed_other) { @@ -267,8 +271,11 @@ void Aggregator::publishData() non_ok_status_depth = depth; msg_to_report = msg; } - if (msg->level < min_level) { - min_level = msg->level; + if ( + msg->level > max_level_without_stale && + msg->level != diagnostic_msgs::msg::DiagnosticStatus::STALE) + { + max_level_without_stale = msg->level; } } // When a non-ok item was found, copy the complete status message once @@ -282,14 +289,16 @@ void Aggregator::publishData() diag_array.header.stamp = clock_->now(); agg_pub_->publish(diag_array); - diag_toplevel_state.level = max_level; - if (max_level < 0 || - (max_level > DiagnosticStatus::ERROR && min_level <= DiagnosticStatus::ERROR)) + if ( + max_level == diagnostic_msgs::msg::DiagnosticStatus::STALE && + max_level_without_stale < diagnostic_msgs::msg::DiagnosticStatus::ERROR) { - // Top level is error if we got no diagnostic level or - // have stale items but not all are stale - diag_toplevel_state.level = DiagnosticStatus::ERROR; + diag_toplevel_state.level = diagnostic_msgs::msg::DiagnosticStatus::STALE; + } else { + diag_toplevel_state.level = max_level_without_stale; } + + last_top_level_state_ = diag_toplevel_state.level; toplevel_state_pub_->publish(diag_toplevel_state); diff --git a/diagnostic_aggregator/src/analyzer_group.cpp b/diagnostic_aggregator/src/analyzer_group.cpp index 0873ac4c..d54a70d3 100644 --- a/diagnostic_aggregator/src/analyzer_group.cpp +++ b/diagnostic_aggregator/src/analyzer_group.cpp @@ -292,7 +292,7 @@ std::vector> AnalyzerGro return output; } - bool all_stale = true; + unsigned char max_level_without_stale = 0; for (auto j = 0u; j < analyzers_.size(); ++j) { std::string path = analyzers_[j]->getPath(); @@ -317,17 +317,23 @@ std::vector> AnalyzerGro kv.key = nice_name; kv.value = processed[i]->message; - all_stale = all_stale && - (processed[i]->level == diagnostic_msgs::msg::DiagnosticStatus::STALE); + if (processed[i]->level != diagnostic_msgs::msg::DiagnosticStatus::STALE) { + max_level_without_stale = max(max_level_without_stale, processed[i]->level); + } header_status->level = max(header_status->level, processed[i]->level); header_status->values.push_back(kv); } } } - // Report stale as errors unless all stale - if (header_status->level == diagnostic_msgs::msg::DiagnosticStatus::STALE && !all_stale) { - header_status->level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + // If one STALE and no ERROR, report STALE + if ( + header_status->level == diagnostic_msgs::msg::DiagnosticStatus::STALE && + max_level_without_stale < diagnostic_msgs::msg::DiagnosticStatus::ERROR) + { + header_status->level = diagnostic_msgs::msg::DiagnosticStatus::STALE; + } else { + header_status->level = max_level_without_stale; } header_status->message = valToMsg(header_status->level); diff --git a/diagnostic_aggregator/test/test_discard_behavior.py b/diagnostic_aggregator/test/test_discard_behavior.py index 18112b0e..164bde29 100644 --- a/diagnostic_aggregator/test/test_discard_behavior.py +++ b/diagnostic_aggregator/test/test_discard_behavior.py @@ -135,7 +135,7 @@ foo_status=None, bar_discard=False, bar_status=None, - agg_expected=DiagnosticStatus.ERROR, # <-- This is the case we are testing for. + agg_expected=DiagnosticStatus.STALE, # <-- This is the case we are testing for. # if one of the children is *not* marked discard_stale := true and # there are no statuses, then the parent should roll up to ERROR. ), @@ -144,7 +144,7 @@ foo_status=DiagnosticStatus.OK, bar_discard=False, bar_status=None, - agg_expected=DiagnosticStatus.ERROR, + agg_expected=DiagnosticStatus.STALE, ), TestMetadata( foo_discard=True,