AP_Logger: do not rotate logs when disarming if we are replay-logging

This commit is contained in:
Peter Barker 2023-04-13 19:20:22 +10:00 committed by Peter Barker
parent 6fbd8df95b
commit 6eda22e7de
1 changed files with 2 additions and 1 deletions

View File

@ -612,7 +612,8 @@ uint16_t AP_Logger_Backend::find_oldest_log()
void AP_Logger_Backend::vehicle_was_disarmed()
{
if (_front._params.file_disarm_rot) {
if (_front._params.file_disarm_rot &&
!_front._params.log_replay) {
// rotate our log. Closing the current one and letting the
// logging restart naturally based on log_disarmed should do
// the trick: