From 3ebc69320cabcbcb1d4f3332e0c7542337387a62 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 2 Oct 2019 11:05:56 +1000 Subject: [PATCH] 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 --- libraries/AP_Logger/AP_Logger_File.cpp | 8 +++++++- libraries/AP_Logger/AP_Logger_File.h | 3 +++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 4cb436d957..b5b2a32948 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -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; } } diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 59f3fece8a..85d00b2c89 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -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