mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: support SDMMC2 for sdcard
This commit is contained in:
parent
281b8eb234
commit
25324ae0e2
|
@ -476,4 +476,6 @@
|
|||
// limit ISR count per byte
|
||||
#define STM32_I2C_ISR_LIMIT 6
|
||||
|
||||
|
||||
#ifndef STM32_SDC_USE_SDMMC2
|
||||
#define STM32_SDC_USE_SDMMC2 FALSE
|
||||
#endif
|
||||
|
|
|
@ -706,6 +706,13 @@ def write_mcu_config(f):
|
|||
f.write('#define HAL_USE_SDC TRUE\n')
|
||||
build_flags.append('USE_FATFS=yes')
|
||||
env_vars['WITH_FATFS'] = "1"
|
||||
elif have_type_prefix('SDMMC2'):
|
||||
f.write('// SDMMC2 available, enable POSIX filesystem support\n')
|
||||
f.write('#define USE_POSIX\n\n')
|
||||
f.write('#define HAL_USE_SDC TRUE\n')
|
||||
f.write('#define STM32_SDC_USE_SDMMC2 TRUE\n')
|
||||
build_flags.append('USE_FATFS=yes')
|
||||
env_vars['WITH_FATFS'] = "1"
|
||||
elif have_type_prefix('SDMMC'):
|
||||
f.write('// SDMMC available, enable POSIX filesystem support\n')
|
||||
f.write('#define USE_POSIX\n\n')
|
||||
|
|
|
@ -55,10 +55,16 @@ bool sdcard_init()
|
|||
uint8_t sd_slowdown = AP_BoardConfig::get_sdcard_slowdown();
|
||||
#if HAL_USE_SDC
|
||||
|
||||
if (SDCD1.bouncebuffer == nullptr) {
|
||||
#if STM32_SDC_USE_SDMMC2 == TRUE
|
||||
auto &sdcd = SDCD2;
|
||||
#else
|
||||
auto &sdcd = SDCD1;
|
||||
#endif
|
||||
|
||||
if (sdcd.bouncebuffer == nullptr) {
|
||||
// allocate 4k bouncebuffer for microSD to match size in
|
||||
// AP_Logger
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer, 4096, true);
|
||||
bouncebuffer_init(&sdcd.bouncebuffer, 4096, true);
|
||||
}
|
||||
|
||||
if (sdcard_running) {
|
||||
|
@ -68,14 +74,14 @@ bool sdcard_init()
|
|||
const uint8_t tries = 3;
|
||||
for (uint8_t i=0; i<tries; i++) {
|
||||
sdcconfig.slowdown = sd_slowdown;
|
||||
sdcStart(&SDCD1, &sdcconfig);
|
||||
if(sdcConnect(&SDCD1) == HAL_FAILED) {
|
||||
sdcStop(&SDCD1);
|
||||
sdcStart(&sdcd, &sdcconfig);
|
||||
if(sdcConnect(&sdcd) == HAL_FAILED) {
|
||||
sdcStop(&sdcd);
|
||||
continue;
|
||||
}
|
||||
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
||||
sdcDisconnect(&SDCD1);
|
||||
sdcStop(&SDCD1);
|
||||
sdcDisconnect(&sdcd);
|
||||
sdcStop(&sdcd);
|
||||
continue;
|
||||
}
|
||||
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||
|
@ -140,9 +146,14 @@ void sdcard_stop(void)
|
|||
f_mount(nullptr, "/", 1);
|
||||
#endif
|
||||
#if HAL_USE_SDC
|
||||
#if STM32_SDC_USE_SDMMC2 == TRUE
|
||||
auto &sdcd = SDCD2;
|
||||
#else
|
||||
auto &sdcd = SDCD1;
|
||||
#endif
|
||||
if (sdcard_running) {
|
||||
sdcDisconnect(&SDCD1);
|
||||
sdcStop(&SDCD1);
|
||||
sdcDisconnect(&sdcd);
|
||||
sdcStop(&sdcd);
|
||||
sdcard_running = false;
|
||||
}
|
||||
#elif HAL_USE_MMC_SPI
|
||||
|
|
Loading…
Reference in New Issue