mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 07:58:28 -04:00
AP_Logger: fixed LOG_FILE_DSRMROT with delayed log stop
now that we persist logging for 15s after disarm we need to also delay the log rotation if LOG_FILE_DSRMROT=1. Otherwise we will put the log data into the next log, which defeats the purpose of the 15s persistance
This commit is contained in:
parent
b89c60d5b0
commit
3ebc69320c
libraries/AP_Logger
@ -129,6 +129,12 @@ bool AP_Logger_File::log_exists(const uint16_t lognum) const
|
||||
|
||||
void AP_Logger_File::periodic_1Hz()
|
||||
{
|
||||
if (_rotate_pending && !logging_enabled()) {
|
||||
_rotate_pending = false;
|
||||
// handle log rotation once we stop logging
|
||||
stop_logging();
|
||||
}
|
||||
|
||||
if (!io_thread_alive()) {
|
||||
if (io_thread_warning_decimation_counter == 0 && _initialised) {
|
||||
// we don't print this error unless we did initialise. When _initialised is set to true
|
||||
@ -1077,7 +1083,7 @@ void AP_Logger_File::vehicle_was_disarmed()
|
||||
// rotate our log. Closing the current one and letting the
|
||||
// logging restart naturally based on log_disarmed should do
|
||||
// the trick:
|
||||
stop_logging();
|
||||
_rotate_pending = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -87,6 +87,9 @@ private:
|
||||
|
||||
uint16_t _cached_oldest_log;
|
||||
|
||||
// should we rotate when we next stop logging
|
||||
bool _rotate_pending;
|
||||
|
||||
uint16_t _log_num_from_list_entry(const uint16_t list_entry);
|
||||
|
||||
// possibly time-consuming preparations handling
|
||||
|
Loading…
Reference in New Issue
Block a user