From ee50eaf3c9cf2f4169e43372ff813fad2ff18035 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 24 Oct 2020 12:26:44 +1100 Subject: [PATCH] HAL_ChibiOS: go via AP_Filesystem for mount/unmount operations this fixes a deadlock where a mount/unmount could access FATFS without holding the AP_Filesystem semaphore --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 12 ++++++++---- libraries/AP_HAL_ChibiOS/Storage.cpp | 5 ++--- libraries/AP_HAL_ChibiOS/Util.cpp | 10 ---------- libraries/AP_HAL_ChibiOS/Util.h | 7 ------- libraries/AP_HAL_ChibiOS/sdcard.cpp | 10 ++++------ 5 files changed, 14 insertions(+), 30 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 4a761480c3..2998267876 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -36,8 +36,8 @@ #include #include "hwdef/common/stm32_util.h" #include "hwdef/common/watchdog.h" +#include #include "shared_dma.h" -#include "sdcard.h" #if HAL_WITH_IO_MCU #include @@ -258,8 +258,8 @@ void Scheduler::reboot(bool hold_in_bootloader) AP::logger().StopLogging(); } - // stop sdcard driver, if active - sdcard_stop(); + // unmount filesystem, if active + AP::FS().unmount(); #endif #if !defined(NO_FASTBOOT) @@ -465,22 +465,26 @@ void Scheduler::_io_thread(void* arg) while (!sched->_hal_initialized) { sched->delay_microseconds(1000); } +#ifndef HAL_NO_LOGGING uint32_t last_sd_start_ms = AP_HAL::millis(); +#endif while (true) { sched->delay_microseconds(1000); // run registered IO processes sched->_run_io(); +#ifndef HAL_NO_LOGGING if (!hal.util->get_soft_armed()) { // if sdcard hasn't mounted then retry it every 3s in the IO // thread when disarmed uint32_t now = AP_HAL::millis(); if (now - last_sd_start_ms > 3000) { last_sd_start_ms = now; - sdcard_retry(); + AP::FS().retry_mount(); } } +#endif } } diff --git a/libraries/AP_HAL_ChibiOS/Storage.cpp b/libraries/AP_HAL_ChibiOS/Storage.cpp index e91f7ce66f..a137332ba5 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.cpp +++ b/libraries/AP_HAL_ChibiOS/Storage.cpp @@ -22,7 +22,6 @@ #include "Scheduler.h" #include "hwdef/common/flash.h" #include -#include "sdcard.h" #include using namespace ChibiOS; @@ -88,7 +87,7 @@ void Storage::_storage_open(void) } // use microSD based storage - if (sdcard_retry()) { + if (AP::FS().retry_mount()) { log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT); if (log_fd == -1) { ::printf("open failed of " HAL_STORAGE_FILE "\n"); @@ -145,7 +144,7 @@ void Storage::_save_backup(void) // We want to do this desperately, // So we keep trying this for a second uint32_t start_millis = AP_HAL::millis(); - while(!sdcard_retry() && (AP_HAL::millis() - start_millis) < 1000) { + while(!AP::FS().retry_mount() && (AP_HAL::millis() - start_millis) < 1000) { hal.scheduler->delay(1); } diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index 9342293ff6..3bf4431454 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -288,16 +288,6 @@ bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len) return true; } -#ifdef USE_POSIX -/* - initialise filesystem - */ -bool Util::fs_init(void) -{ - return sdcard_retry(); -} -#endif - // return true if the reason for the reboot was a watchdog reset bool Util::was_watchdog_reset() const { diff --git a/libraries/AP_HAL_ChibiOS/Util.h b/libraries/AP_HAL_ChibiOS/Util.h index f4143e4219..3e4b01c641 100644 --- a/libraries/AP_HAL_ChibiOS/Util.h +++ b/libraries/AP_HAL_ChibiOS/Util.h @@ -55,13 +55,6 @@ public: void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override; #endif -#ifdef USE_POSIX - /* - initialise (or re-initialise) filesystem storage - */ - bool fs_init(void) override; -#endif - // return true if the reason for the reboot was a watchdog reset bool was_watchdog_reset() const override; diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index 7fbd64a292..c01804636f 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -80,8 +80,6 @@ bool sdcard_init() } printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown); - // Create APM Directory if needed - AP::FS().mkdir("/APM"); sdcard_running = true; return true; } @@ -124,9 +122,6 @@ bool sdcard_init() continue; } printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown); - - // Create APM Directory if needed - AP::FS().mkdir("/APM"); return true; } #endif @@ -163,7 +158,10 @@ bool sdcard_retry(void) { #ifdef USE_POSIX if (!sdcard_running) { - sdcard_init(); + if (sdcard_init()) { + // create APM directory + AP::FS().mkdir("/APM"); + } } return sdcard_running; #endif