AP_Logger: avoid logging duplicate FMT/UNIT/FMTU/MULT messages

Failing due to being out of time meant we wouldn't incremement the counter, even though we'd emitted the item.

it is important we try to send something, so move this check to be after we increment whichever counter we are using.
This commit is contained in:
Peter Barker 2023-01-17 13:35:14 +11:00 committed by Andrew Tridgell
parent 9be7efb706
commit 553e320915
1 changed files with 20 additions and 10 deletions

View File

@ -95,11 +95,13 @@ void LoggerMessageWriter_DFLogStart::process()
case Stage::FORMATS: case Stage::FORMATS:
// write log formats so the log is self-describing // write log formats so the log is self-describing
while (next_format_to_send < _logger_backend->num_types()) { while (next_format_to_send < _logger_backend->num_types()) {
if (!_logger_backend->Write_Format(_logger_backend->structure(next_format_to_send)) || if (!_logger_backend->Write_Format(_logger_backend->structure(next_format_to_send))) {
check_process_limit(start_us)) {
return; // call me again! return; // call me again!
} }
next_format_to_send++; next_format_to_send++;
if (check_process_limit(start_us)) {
return; // call me again!
}
} }
_fmt_done = true; _fmt_done = true;
stage = Stage::PARMS; stage = Stage::PARMS;
@ -107,12 +109,14 @@ void LoggerMessageWriter_DFLogStart::process()
case Stage::PARMS: { case Stage::PARMS: {
while (ap) { while (ap) {
if (!_logger_backend->Write_Parameter(ap, token, type, param_default) || if (!_logger_backend->Write_Parameter(ap, token, type, param_default)) {
check_process_limit(start_us)) {
return; return;
} }
param_default = AP::logger().quiet_nanf(); param_default = AP::logger().quiet_nanf();
ap = AP_Param::next_scalar(&token, &type, &param_default); ap = AP_Param::next_scalar(&token, &type, &param_default);
if (check_process_limit(start_us)) {
return; // call me again!
}
} }
_params_done = true; _params_done = true;
@ -122,33 +126,39 @@ void LoggerMessageWriter_DFLogStart::process()
case Stage::UNITS: case Stage::UNITS:
while (_next_unit_to_send < _logger_backend->num_units()) { while (_next_unit_to_send < _logger_backend->num_units()) {
if (!_logger_backend->Write_Unit(_logger_backend->unit(_next_unit_to_send)) || if (!_logger_backend->Write_Unit(_logger_backend->unit(_next_unit_to_send))) {
check_process_limit(start_us)) {
return; // call me again! return; // call me again!
} }
_next_unit_to_send++; _next_unit_to_send++;
if (check_process_limit(start_us)) {
return; // call me again!
}
} }
stage = Stage::MULTIPLIERS; stage = Stage::MULTIPLIERS;
FALLTHROUGH; FALLTHROUGH;
case Stage::MULTIPLIERS: case Stage::MULTIPLIERS:
while (_next_multiplier_to_send < _logger_backend->num_multipliers()) { while (_next_multiplier_to_send < _logger_backend->num_multipliers()) {
if (!_logger_backend->Write_Multiplier(_logger_backend->multiplier(_next_multiplier_to_send)) || if (!_logger_backend->Write_Multiplier(_logger_backend->multiplier(_next_multiplier_to_send))) {
check_process_limit(start_us)) {
return; // call me again! return; // call me again!
} }
_next_multiplier_to_send++; _next_multiplier_to_send++;
if (check_process_limit(start_us)) {
return; // call me again!
}
} }
stage = Stage::UNITS; stage = Stage::UNITS;
FALLTHROUGH; FALLTHROUGH;
case Stage::FORMAT_UNITS: case Stage::FORMAT_UNITS:
while (_next_format_unit_to_send < _logger_backend->num_types()) { while (_next_format_unit_to_send < _logger_backend->num_types()) {
if (!_logger_backend->Write_Format_Units(_logger_backend->structure(_next_format_unit_to_send)) || if (!_logger_backend->Write_Format_Units(_logger_backend->structure(_next_format_unit_to_send))) {
check_process_limit(start_us)) {
return; // call me again! return; // call me again!
} }
_next_format_unit_to_send++; _next_format_unit_to_send++;
if (check_process_limit(start_us)) {
return; // call me again!
}
} }
stage = Stage::RUNNING_SUBWRITERS; stage = Stage::RUNNING_SUBWRITERS;
FALLTHROUGH; FALLTHROUGH;