From 8ae221eeb4719749cd8eea85626135f74cbf8e60 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 14 Jun 2021 09:46:01 +1000 Subject: [PATCH] AP_Filesystem: removed the 3s grace period for file ops when armed log file open now needs to happen in the logging thread --- libraries/AP_Filesystem/AP_Filesystem_backend.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp index c4e680025b..87fe694d9e 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_backend.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_backend.cpp @@ -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; }