From b03024dd346f4f4adcb8c090cb051b78a3a475ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 29 Dec 2018 10:50:17 +1100 Subject: [PATCH] HAL_ChibiOS: allow mount of microSD after boot when disarmed, try to mount sd card every 3s --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 10 ++++++++++ libraries/AP_HAL_ChibiOS/sdcard.cpp | 13 +++++++++++-- libraries/AP_HAL_ChibiOS/sdcard.h | 1 + 3 files changed, 22 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 6c98a234ad..de388ee50c 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -351,11 +351,21 @@ void Scheduler::_io_thread(void* arg) while (!sched->_hal_initialized) { sched->delay_microseconds(1000); } + uint32_t last_sd_start_ms = AP_HAL::millis(); while (true) { sched->delay_microseconds(1000); // run registered IO processes sched->_run_io(); + + 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) { + sdcard_retry(); + } + } } } diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index 4f43b65159..43cbda3ca8 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -18,12 +18,14 @@ #include "sdcard.h" #include "hwdef/common/spi_hook.h" #include +#include extern const AP_HAL::HAL& hal; #ifdef USE_POSIX static FATFS SDC_FS; // FATFS object static bool sdcard_running; +static HAL_Semaphore sem; #endif #if HAL_USE_SDC @@ -48,6 +50,8 @@ static SPIConfig highspeed; bool sdcard_init() { #ifdef USE_POSIX + WITH_SEMAPHORE(sem); + uint8_t sd_slowdown = AP_BoardConfig::get_sdcard_slowdown(); #if HAL_USE_SDC @@ -61,7 +65,6 @@ bool sdcard_init() const uint8_t tries = 3; for (uint8_t i=0; idelay(10); sdcconfig.slowdown = sd_slowdown; sdcStart(&SDCD1, &sdcconfig); if(sdcConnect(&SDCD1) == HAL_FAILED) { @@ -106,7 +109,6 @@ bool sdcard_init() */ const uint8_t tries = 3; for (uint8_t i=0; idelay(10); mmcStart(&MMCD1, &mmcconfig); if (mmcConnect(&MMCD1) == HAL_FAILED) { @@ -154,6 +156,13 @@ void sdcard_stop(void) #endif } +void sdcard_retry(void) +{ + if (!sdcard_running) { + sdcard_init(); + } +} + #if HAL_USE_MMC_SPI /* diff --git a/libraries/AP_HAL_ChibiOS/sdcard.h b/libraries/AP_HAL_ChibiOS/sdcard.h index 6a6cb6c196..766debcbb5 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.h +++ b/libraries/AP_HAL_ChibiOS/sdcard.h @@ -17,3 +17,4 @@ bool sdcard_init(); void sdcard_stop(); +void sdcard_retry();