Browse Source

AP_Logger: process pending rotate on arming

If the user arms the vehicle during the logging-persist-timeout we
should rotate the log immediately.
c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
115751833b
  1. 4
      libraries/AP_Logger/AP_Logger_File.cpp

4
libraries/AP_Logger/AP_Logger_File.cpp

@ -767,6 +767,10 @@ void AP_Logger_File::stop_logging(void) @@ -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…
Cancel
Save