AP_Logger: do not rotate logs when disarming if we are replay-logging
This commit is contained in:
parent
6fbd8df95b
commit
6eda22e7de
@ -612,7 +612,8 @@ uint16_t AP_Logger_Backend::find_oldest_log()
|
|||||||
|
|
||||||
void AP_Logger_Backend::vehicle_was_disarmed()
|
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
|
// rotate our log. Closing the current one and letting the
|
||||||
// logging restart naturally based on log_disarmed should do
|
// logging restart naturally based on log_disarmed should do
|
||||||
// the trick:
|
// the trick:
|
||||||
|
Loading…
Reference in New Issue
Block a user