mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Logger: fixed log creation on forced arm
when we force arm we need to ask the IO thread to create the log, not create it ourselves
This commit is contained in:
parent
080ebe9cb2
commit
a757706797
@ -134,14 +134,19 @@ void AP_Logger_File::periodic_1Hz()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (_initialised &&
|
if (_initialised &&
|
||||||
|
!start_new_log_pending &&
|
||||||
_write_fd == -1 && _read_fd == -1 &&
|
_write_fd == -1 && _read_fd == -1 &&
|
||||||
logging_enabled() &&
|
logging_enabled() &&
|
||||||
!recent_open_error() &&
|
!recent_open_error()) {
|
||||||
!hal.util->get_soft_armed()) {
|
|
||||||
// retry logging open. This allows for booting with
|
// retry logging open. This allows for booting with
|
||||||
// LOG_DISARMED=1 with a bad microSD or no microSD. Once a
|
// LOG_DISARMED=1 with a bad microSD or no microSD. Once a
|
||||||
// card is inserted then logging starts
|
// card is inserted then logging starts
|
||||||
|
// this also allows for logging to start after forced arming
|
||||||
|
if (!hal.util->get_soft_armed()) {
|
||||||
start_new_log();
|
start_new_log();
|
||||||
|
} else {
|
||||||
|
start_new_log_pending = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!io_thread_alive()) {
|
if (!io_thread_alive()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user