AP_BoardConfig: added BRD_SD_SLOWDOWN parameter

allows for reduction in microSD clock speed
This commit is contained in:
Andrew Tridgell 2018-12-28 12:06:12 +11:00
parent ba379d0b18
commit 3a9d8448b1
2 changed files with 37 additions and 0 deletions

View File

@ -253,6 +253,16 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),
#endif
#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
};
@ -268,6 +278,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

View File

@ -156,6 +156,12 @@ public:
return instance?instance->_vservo_min.get():0;
}
#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;
@ -228,4 +234,8 @@ private:
#if HAL_HAVE_SERVO_VOLTAGE
AP_Float _vservo_min;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
AP_Int8 _sdcard_slowdown;
#endif
};