diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 001b52a74c..1763ba70dc 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -1415,6 +1415,10 @@ bool AP_Logger::log_while_disarmed(void) const uint32_t now = AP_HAL::millis(); uint32_t persist_ms = HAL_LOGGER_ARM_PERSIST*1000U; + if (_force_long_log_persist) { + // log for 10x longer than default + persist_ms *= 10U; + } // keep logging for HAL_LOGGER_ARM_PERSIST seconds after disarming const uint32_t arm_change_ms = hal.util->get_last_armed_change(); diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 89e1aa5536..b25c8da3e7 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -384,6 +384,7 @@ public: // accesss to public parameters void set_force_log_disarmed(bool force_logging) { _force_log_disarmed = force_logging; } + void set_long_log_persist(bool b) { _force_long_log_persist = b; } bool log_while_disarmed(void) const; uint8_t log_replay(void) const { return _params.log_replay; } @@ -537,6 +538,7 @@ private: bool _writes_enabled:1; bool _force_log_disarmed:1; + bool _force_long_log_persist:1; // remember formats for replay void save_format_Replay(const void *pBuffer);