mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: warn on high dropped log message rate
This commit is contained in:
parent
85f8ae8aa3
commit
baa9af2273
|
@ -98,6 +98,7 @@ void AP_Logger_Backend::periodic_tasks()
|
|||
void AP_Logger_Backend::start_new_log_reset_variables()
|
||||
{
|
||||
_dropped = 0;
|
||||
_last_dropped = 0;
|
||||
_startup_messagewriter->reset();
|
||||
_front.backend_starting_new_log(this);
|
||||
_formats_written.clearall();
|
||||
|
|
|
@ -213,6 +213,7 @@ protected:
|
|||
uint16_t _cached_oldest_log;
|
||||
|
||||
uint32_t _dropped;
|
||||
uint32_t _last_dropped;
|
||||
// should we rotate when we next stop logging
|
||||
bool _rotate_pending;
|
||||
|
||||
|
|
|
@ -175,6 +175,11 @@ void AP_Logger_File::periodic_1Hz()
|
|||
// setup rate limiting if log rate max > 0Hz or log pause of streaming entries is requested
|
||||
rate_limiter = NEW_NOTHROW AP_Logger_RateLimiter(_front, _front._params.file_ratemax, _front._params.disarm_ratemax);
|
||||
}
|
||||
|
||||
if (_dropped - _last_dropped > 100) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "AP_Logger: dropping messages (%u/s)", unsigned(_dropped - _last_dropped));
|
||||
}
|
||||
_last_dropped = _dropped;
|
||||
}
|
||||
|
||||
void AP_Logger_File::periodic_fullrate()
|
||||
|
|
Loading…
Reference in New Issue