AP_Filesystem: removed the 3s grace period for file ops when armed

log file open now needs to happen in the logging thread
This commit is contained in:
Andrew Tridgell 2021-06-14 09:46:01 +10:00
parent 132b651968
commit 1106b39d46

View File

@ -71,11 +71,6 @@ bool AP_Filesystem_Backend::file_op_allowed(void) const
if (!hal.util->get_soft_armed() || !hal.scheduler->in_main_thread()) {
return true;
}
if (AP_HAL::millis() - hal.util->get_last_armed_change() < 3000) {
// allow file operations from main thread in first 3s after
// arming to allow for log file creation
return true;
}
return false;
}