mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: avoid all opens of log files in main thread
this fixes a problem with sdcards where file open is very slow. It can trigger a watchdog if it is slow enough. Peter and I hit this issue on a pixracer today with a new sd card
This commit is contained in:
parent
3ad6c5523b
commit
75f7c36bc7
|
@ -130,7 +130,8 @@ void AP_Logger_File::periodic_1Hz()
|
|||
erase.was_logging) {
|
||||
// restart logging after an erase if needed
|
||||
erase.was_logging = false;
|
||||
start_new_log();
|
||||
// setup to open the log in the backend thread
|
||||
start_new_log_pending = true;
|
||||
}
|
||||
|
||||
if (_initialised &&
|
||||
|
@ -138,16 +139,9 @@ void AP_Logger_File::periodic_1Hz()
|
|||
_write_fd == -1 && _read_fd == -1 &&
|
||||
logging_enabled() &&
|
||||
!recent_open_error()) {
|
||||
// retry logging open. This allows for booting with
|
||||
// LOG_DISARMED=1 with a bad microSD or no microSD. Once a
|
||||
// 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();
|
||||
} else {
|
||||
// setup to open the log in the backend thread
|
||||
start_new_log_pending = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (!io_thread_alive()) {
|
||||
if (io_thread_warning_decimation_counter == 0 && _initialised) {
|
||||
|
|
Loading…
Reference in New Issue