mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
HAL_ChibiOS: cope with SDMMC peripheral for microSD
This commit is contained in:
parent
ca28a01bbf
commit
cdbbceb6b6
@ -92,7 +92,7 @@ def get_alt_function(mcu, pin, function):
|
|||||||
# we do software RTS
|
# we do software RTS
|
||||||
return None
|
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:
|
for l in af_labels:
|
||||||
if function.startswith(l):
|
if function.startswith(l):
|
||||||
s = pin + ":" + function
|
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('#define HAL_STDOUT_SERIAL %s\n\n' % get_config('STDOUT_SERIAL'))
|
||||||
f.write('// baudrate used for stdout (printf)\n')
|
f.write('// baudrate used for stdout (printf)\n')
|
||||||
f.write('#define HAL_STDOUT_BAUDRATE %u\n\n' % get_config('STDOUT_BAUDRATE', type=int))
|
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('// SDIO available, enable POSIX filesystem support\n')
|
||||||
f.write('#define USE_POSIX\n\n')
|
f.write('#define USE_POSIX\n\n')
|
||||||
f.write('#define HAL_USE_SDC TRUE\n')
|
f.write('#define HAL_USE_SDC TRUE\n')
|
||||||
@ -935,7 +935,7 @@ def build_peripheral_list():
|
|||||||
peripherals.append(type + "_RX")
|
peripherals.append(type + "_RX")
|
||||||
if type.startswith('ADC'):
|
if type.startswith('ADC'):
|
||||||
peripherals.append(type)
|
peripherals.append(type)
|
||||||
if type.startswith('SDIO'):
|
if type.startswith('SDIO') or type.startswith('SDMMC'):
|
||||||
peripherals.append(type)
|
peripherals.append(type)
|
||||||
if type.startswith('TIM'):
|
if type.startswith('TIM'):
|
||||||
if p.has_extra('RCIN'):
|
if p.has_extra('RCIN'):
|
||||||
|
@ -62,7 +62,7 @@ def chibios_dma_define_name(key):
|
|||||||
return 'STM32_UART_%s_DMA_' % key
|
return 'STM32_UART_%s_DMA_' % key
|
||||||
elif key.startswith('UART'):
|
elif key.startswith('UART'):
|
||||||
return 'STM32_UART_%s_DMA_' % key
|
return 'STM32_UART_%s_DMA_' % key
|
||||||
elif key.startswith('SDIO'):
|
elif key.startswith('SDIO') or key.startswith('SDMMC'):
|
||||||
return 'STM32_SDC_%s_DMA_' % key
|
return 'STM32_SDC_%s_DMA_' % key
|
||||||
elif key.startswith('TIM'):
|
elif key.startswith('TIM'):
|
||||||
return 'STM32_TIM_%s_DMA_' % key
|
return 'STM32_TIM_%s_DMA_' % key
|
||||||
|
Loading…
Reference in New Issue
Block a user