@@ -64,7 +64,9 @@ Aggregator::Aggregator()
64
64
pub_rate_(1.0 ),
65
65
history_depth_(1000 ),
66
66
clock_(n_->get_clock ()),
67
- base_path_(" " )
67
+ base_path_(" " ),
68
+ critical_(false ),
69
+ last_top_level_state_(DiagnosticStatus::STALE)
68
70
{
69
71
RCLCPP_DEBUG (logger_, " constructor" );
70
72
bool other_as_errors = false ;
@@ -88,12 +90,16 @@ Aggregator::Aggregator()
88
90
other_as_errors = param.second .as_bool ();
89
91
} else if (param.first .compare (" history_depth" ) == 0 ) {
90
92
history_depth_ = param.second .as_int ();
93
+ } else if (param.first .compare (" critical" ) == 0 ) {
94
+ critical_ = param.second .as_bool ();
91
95
}
92
96
}
93
97
RCLCPP_DEBUG (logger_, " Aggregator publication rate configured to: %f" , pub_rate_);
94
98
RCLCPP_DEBUG (logger_, " Aggregator base path configured to: %s" , base_path_.c_str ());
95
99
RCLCPP_DEBUG (
96
100
logger_, " Aggregator other_as_errors configured to: %s" , (other_as_errors ? " true" : " false" ));
101
+ RCLCPP_DEBUG (
102
+ logger_, " Aggregator critical publisher configured to: %s" , (critical_ ? " true" : " false" ));
97
103
98
104
analyzer_group_ = std::make_unique<AnalyzerGroup>();
99
105
if (!analyzer_group_->init (base_path_, " " , n_)) {
@@ -149,6 +155,23 @@ void Aggregator::diagCallback(const DiagnosticArray::SharedPtr diag_msg)
149
155
std::lock_guard<std::mutex> lock (mutex_);
150
156
for (auto j = 0u ; j < diag_msg->status .size (); ++j) {
151
157
analyzed = false ;
158
+
159
+ const bool top_level_state_transition_to_error = (last_top_level_state_ != DiagnosticStatus::ERROR)
160
+ && (diag_msg->status [j].level == DiagnosticStatus::ERROR);
161
+
162
+ if (critical_ && top_level_state_transition_to_error) {
163
+ RCLCPP_DEBUG (
164
+ logger_, " Received error message: %s, publishing error immediately" ,
165
+ diag_msg->status [j].name .c_str ());
166
+ DiagnosticStatus diag_toplevel_state;
167
+ diag_toplevel_state.name = " toplevel_state_critical" ;
168
+ diag_toplevel_state.level = diag_msg->status [j].level ;
169
+ toplevel_state_pub_->publish (diag_toplevel_state);
170
+
171
+ // store the last published state
172
+ last_top_level_state_ = diag_toplevel_state.level ;
173
+ }
174
+
152
175
auto item = std::make_shared<StatusItem>(&diag_msg->status [j]);
153
176
154
177
if (analyzer_group_->match (item->getName ())) {
@@ -217,6 +240,8 @@ void Aggregator::publishData()
217
240
// have stale items but not all are stale
218
241
diag_toplevel_state.level = DiagnosticStatus::ERROR;
219
242
}
243
+ last_top_level_state_ = diag_toplevel_state.level ;
244
+
220
245
toplevel_state_pub_->publish (diag_toplevel_state);
221
246
}
222
247
0 commit comments