mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: process pending rotate on arming
If the user arms the vehicle during the logging-persist-timeout we should rotate the log immediately.
This commit is contained in:
parent
f6b121ad87
commit
115751833b
|
@ -767,6 +767,10 @@ void AP_Logger_File::stop_logging(void)
|
|||
|
||||
void AP_Logger_File::PrepForArming()
|
||||
{
|
||||
if (_rotate_pending) {
|
||||
_rotate_pending = false;
|
||||
stop_logging();
|
||||
}
|
||||
if (logging_started()) {
|
||||
return;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue