From cdbbceb6b6d1fbafd46ef8fc8bd4e8da209cba63 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Mar 2018 13:57:33 +1100 Subject: [PATCH] HAL_ChibiOS: cope with SDMMC peripheral for microSD --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 6 +++--- libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index c2c2bc47bc..6981aa69a3 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -92,7 +92,7 @@ def get_alt_function(mcu, pin, function): # we do software RTS return None - af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'OTG', 'JT', 'TIM', 'CAN'] + af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'SDMMC', 'OTG', 'JT', 'TIM', 'CAN'] for l in af_labels: if function.startswith(l): s = pin + ":" + function @@ -313,7 +313,7 @@ def write_mcu_config(f): f.write('#define HAL_STDOUT_SERIAL %s\n\n' % get_config('STDOUT_SERIAL')) f.write('// baudrate used for stdout (printf)\n') f.write('#define HAL_STDOUT_BAUDRATE %u\n\n' % get_config('STDOUT_BAUDRATE', type=int)) - if 'SDIO' in bytype: + if have_type_prefix('SDIO') or have_type_prefix('SDMMC'): f.write('// SDIO available, enable POSIX filesystem support\n') f.write('#define USE_POSIX\n\n') f.write('#define HAL_USE_SDC TRUE\n') @@ -935,7 +935,7 @@ def build_peripheral_list(): peripherals.append(type + "_RX") if type.startswith('ADC'): peripherals.append(type) - if type.startswith('SDIO'): + if type.startswith('SDIO') or type.startswith('SDMMC'): peripherals.append(type) if type.startswith('TIM'): if p.has_extra('RCIN'): diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py index e1b6e4da3a..f83e7f9e7f 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py @@ -62,7 +62,7 @@ def chibios_dma_define_name(key): return 'STM32_UART_%s_DMA_' % key elif key.startswith('UART'): return 'STM32_UART_%s_DMA_' % key - elif key.startswith('SDIO'): + elif key.startswith('SDIO') or key.startswith('SDMMC'): return 'STM32_SDC_%s_DMA_' % key elif key.startswith('TIM'): return 'STM32_TIM_%s_DMA_' % key