Skip to content

Commit 1d73654

Browse files
style: rename "deepness" to "depth"
1 parent fcc4cfc commit 1d73654

File tree

1 file changed

+12
-12
lines changed

1 file changed

+12
-12
lines changed

diagnostic_aggregator/src/aggregator.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -227,8 +227,8 @@ void Aggregator::publishData()
227227
diag_toplevel_state.name = "toplevel_state";
228228
diag_toplevel_state.level = -1;
229229
int min_level = 255;
230-
uint non_ok_status_deepness = 0;
231-
uint deepness = 0;
230+
uint non_ok_status_depth = 0;
231+
uint depth = 0;
232232
uint report_idx = 0;
233233

234234
vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed;
@@ -240,17 +240,17 @@ void Aggregator::publishData()
240240
{
241241
diag_array.status.push_back(*processed[i]);
242242

243-
deepness = static_cast<uint>(std::count(processed[i]->name.begin(), processed[i]->name.end(), '/'));
243+
depth = static_cast<uint>(std::count(processed[i]->name.begin(), processed[i]->name.end(), '/'));
244244
if (processed[i]->level > diag_toplevel_state.level)
245245
{
246246
diag_toplevel_state.level = processed[i]->level;
247-
non_ok_status_deepness = deepness;
247+
non_ok_status_depth = depth;
248248
report_idx = i;
249249
}
250-
if (processed[i]->level == diag_toplevel_state.level && deepness > non_ok_status_deepness)
250+
if (processed[i]->level == diag_toplevel_state.level && depth > non_ok_status_depth)
251251
{
252252
// On non okay diagnostics also copy the deepest message to toplevel state
253-
non_ok_status_deepness = deepness;
253+
non_ok_status_depth = depth;
254254
report_idx = i;
255255
}
256256
if (processed[i]->level < min_level)
@@ -268,7 +268,7 @@ void Aggregator::publishData()
268268
}
269269

270270
/* Process other category (unmapped items) */
271-
non_ok_status_deepness = 0;
271+
non_ok_status_depth = 0;
272272
report_idx = 0;
273273
vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> > processed_other;
274274
{
@@ -279,25 +279,25 @@ void Aggregator::publishData()
279279
{
280280
diag_array.status.push_back(*processed_other[i]);
281281

282-
deepness = static_cast<uint>(std::count(processed[i]->name.begin(), processed[i]->name.end(), '/'));
282+
depth = static_cast<uint>(std::count(processed[i]->name.begin(), processed[i]->name.end(), '/'));
283283
if (processed_other[i]->level > diag_toplevel_state.level)
284284
{
285285
diag_toplevel_state.level = processed_other[i]->level;
286-
non_ok_status_deepness = deepness;
286+
non_ok_status_depth = depth;
287287
report_idx = i;
288288
}
289-
if (processed_other[i]->level == diag_toplevel_state.level && deepness > non_ok_status_deepness)
289+
if (processed_other[i]->level == diag_toplevel_state.level && depth > non_ok_status_depth)
290290
{
291291
// On non okay diagnostics also copy the deepest message to toplevel state
292-
non_ok_status_deepness = deepness;
292+
non_ok_status_depth = depth;
293293
report_idx = i;
294294
}
295295
if (processed_other[i]->level < min_level)
296296
{
297297
min_level = processed_other[i]->level;
298298
}
299299
// When a non-ok item was found AND it was reported in 'other' categpry, copy the complete status message once
300-
if (diag_toplevel_state.level > diagnostic_msgs::DiagnosticStatus::OK && non_ok_status_deepness > 0)
300+
if (diag_toplevel_state.level > diagnostic_msgs::DiagnosticStatus::OK && non_ok_status_depth > 0)
301301
{
302302
diag_toplevel_state.name = processed_other[report_idx]->name;
303303
diag_toplevel_state.message = processed_other[report_idx]->message;

0 commit comments

Comments
 (0)