From 274dc0b9bd2c88f292e8a948c94349d199c82c31 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 28 Dec 2018 12:06:12 +1100 Subject: [PATCH] AP_BoardConfig: added BRD_SD_SLOWDOWN parameter allows for reduction in microSD clock speed --- libraries/AP_BoardConfig/AP_BoardConfig.cpp | 27 +++++++++++++++++++++ libraries/AP_BoardConfig/AP_BoardConfig.h | 11 ++++++++- 2 files changed, 37 insertions(+), 1 deletion(-) diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 62f5c0d66e..7be312e7f7 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -223,6 +223,16 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Path: ../AP_RTC/AP_RTC.cpp AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC), +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + // @Param: SD_SLOWDOWN + // @DisplayName: microSD slowdown + // @Description: This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used. + // @Range: 0 32 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("SD_SLOWDOWN", 17, AP_BoardConfig, _sdcard_slowdown, 0), +#endif + AP_GROUPEND }; @@ -238,6 +248,23 @@ void AP_BoardConfig::init() #endif AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW); + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(USE_POSIX) + uint8_t slowdown = constrain_int16(_sdcard_slowdown.get(), 0, 32); + const uint8_t max_slowdown = 8; + do { + if (hal.util->fs_init()) { + break; + } + slowdown++; + hal.scheduler->delay(5); + } while (slowdown < max_slowdown); + if (slowdown < max_slowdown) { + _sdcard_slowdown.set(slowdown); + } else { + printf("SDCard failed to start\n"); + } +#endif } // set default value for BRD_SAFETY_MASK diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index a59f440f11..3d274e6295 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -149,7 +149,12 @@ public: #endif } - +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + static uint8_t get_sdcard_slowdown(void) { + return instance?instance->_sdcard_slowdown.get():0; + } +#endif + private: static AP_BoardConfig *instance; @@ -216,4 +221,8 @@ private: // real-time-clock; private because access is via the singleton AP_RTC rtc; + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + AP_Int8 _sdcard_slowdown; +#endif };