mirror of https://github.com/ArduPilot/ardupilot
376 lines
9.8 KiB
Python
376 lines
9.8 KiB
Python
#!/usr/bin/env python
|
|
'''
|
|
these tables are generated from the STM32 datasheets for the
|
|
STM32F732
|
|
'''
|
|
|
|
# additional build information for ChibiOS
|
|
build = {
|
|
"CHIBIOS_STARTUP_MK" : "os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f7xx.mk",
|
|
"CHIBIOS_PLATFORM_MK" : "os/hal/ports/STM32/STM32F7xx/platform.mk"
|
|
}
|
|
|
|
# MCU parameters
|
|
mcu = {
|
|
# ram map, as list of (address, size-kb, flags)
|
|
# flags of 1 means DMA-capable
|
|
# flags of 2 means faster memory for CPU intensive work
|
|
'RAM_MAP' : [
|
|
(0x20000000, 64, 3), # DTCM
|
|
(0x20010000, 176, 0), # SRAM1
|
|
(0x2003C000, 16, 0), # SRAM2
|
|
(0x00001000, 15, 0), # ITCM, dropping first 1k
|
|
],
|
|
|
|
'EXPECTED_CLOCK' : 216000000,
|
|
|
|
'DEFINES' : {
|
|
'STM32F7' : '1',
|
|
},
|
|
|
|
# this board has M7 instructions, but single precision only FPU
|
|
# we build as m4 as it makes for a smaller build, and given the 1M
|
|
# flash limit we care more about size
|
|
'CORTEX' : 'cortex-m4',
|
|
'CPU_FLAGS' : '-mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard'
|
|
}
|
|
|
|
DMA_Map = {
|
|
# format is (DMA_TABLE, StreamNum, Channel)
|
|
# extracted from tabula-STM32F732-DMA.csv
|
|
"ADC1" : [(2,0,0),(2,4,0)],
|
|
"ADC2" : [(2,2,1),(2,3,1)],
|
|
"ADC3" : [(2,0,2),(2,1,2)],
|
|
"AES_IN" : [(2,6,2)],
|
|
"AES_OUT" : [(2,5,2)],
|
|
"DAC1" : [(1,5,7)],
|
|
"DAC2" : [(1,6,7)],
|
|
"I2C1_RX" : [(1,0,1),(1,5,1)],
|
|
"I2C1_TX" : [(1,6,1),(1,7,1)],
|
|
"I2C2_RX" : [(1,2,7),(1,3,7)],
|
|
"I2C2_TX" : [(1,7,7)],
|
|
"I2C3_RX" : [(1,1,1),(1,2,3)],
|
|
"I2C3_TX" : [(1,4,3)],
|
|
"QUADSPI" : [(2,7,3)],
|
|
"SAI1_A" : [(2,1,0),(2,3,0)],
|
|
"SAI1_B" : [(2,5,0),(2,4,1)],
|
|
"SAI2_A" : [(2,4,3)],
|
|
"SAI2_B" : [(2,7,0),(2,6,3)],
|
|
"SDMMC1" : [(2,3,4),(2,6,4)],
|
|
"SDMMC2" : [(2,0,11),(2,5,11)],
|
|
"SPI1_RX" : [(2,0,3),(2,2,3)],
|
|
"SPI1_TX" : [(2,3,3),(2,5,3)],
|
|
"SPI2_RX" : [(1,3,0)],
|
|
"SPI2_TX" : [(1,4,0)],
|
|
"SPI3_RX" : [(1,0,0),(1,2,0)],
|
|
"SPI3_TX" : [(1,5,0),(1,7,0)],
|
|
"SPI4_RX" : [(2,0,4),(2,3,5)],
|
|
"SPI4_TX" : [(2,1,4),(2,4,5)],
|
|
"SPI5_RX" : [(2,3,2),(2,5,7)],
|
|
"SPI5_TX" : [(2,4,2),(2,6,7)],
|
|
"TIM1_CH1" : [(2,6,0),(2,1,6),(2,3,6)],
|
|
"TIM1_CH2" : [(2,6,0),(2,2,6)],
|
|
"TIM1_CH3" : [(2,6,0),(2,6,6)],
|
|
"TIM1_CH4" : [(2,4,6)],
|
|
"TIM1_COM" : [(2,4,6)],
|
|
"TIM1_TRIG" : [(2,0,6),(2,4,6)],
|
|
"TIM1_UP" : [(2,5,6)],
|
|
"TIM2_CH1" : [(1,5,3)],
|
|
"TIM2_CH2" : [(1,6,3)],
|
|
"TIM2_CH3" : [(1,1,3)],
|
|
"TIM2_CH4" : [(1,6,3),(1,7,3)],
|
|
"TIM2_UP" : [(1,1,3),(1,7,3)],
|
|
"TIM3_CH1" : [(1,4,5)],
|
|
"TIM3_CH2" : [(1,5,5)],
|
|
"TIM3_CH3" : [(1,7,5)],
|
|
"TIM3_CH4" : [(1,2,5)],
|
|
"TIM3_TRIG" : [(1,4,5)],
|
|
"TIM3_UP" : [(1,2,5)],
|
|
"TIM4_CH1" : [(1,0,2)],
|
|
"TIM4_CH2" : [(1,3,2)],
|
|
"TIM4_CH3" : [(1,7,2)],
|
|
"TIM4_UP" : [(1,6,2)],
|
|
"TIM5_CH1" : [(1,2,6)],
|
|
"TIM5_CH2" : [(1,4,6)],
|
|
"TIM5_CH3" : [(1,0,6)],
|
|
"TIM5_CH4" : [(1,1,6),(1,3,6)],
|
|
"TIM5_TRIG" : [(1,1,6),(1,3,6)],
|
|
"TIM5_UP" : [(1,0,6),(1,6,6)],
|
|
"TIM6_UP" : [(1,1,7)],
|
|
"TIM7_UP" : [(1,2,1),(1,4,1)],
|
|
"TIM8_CH1" : [(2,2,0),(2,2,7)],
|
|
"TIM8_CH2" : [(2,2,0),(2,3,7)],
|
|
"TIM8_CH3" : [(2,2,0),(2,4,7)],
|
|
"TIM8_CH4" : [(2,7,7)],
|
|
"TIM8_COM" : [(2,7,7)],
|
|
"TIM8_TRIG" : [(2,7,7)],
|
|
"TIM8_UP" : [(2,1,7)],
|
|
"UART4_RX" : [(1,2,4)],
|
|
"UART4_TX" : [(1,4,4)],
|
|
"UART5_RX" : [(1,0,4)],
|
|
"UART5_TX" : [(1,7,4)],
|
|
"UART7_RX" : [(1,3,5)],
|
|
"UART7_TX" : [(1,1,5)],
|
|
"UART8_RX" : [(1,6,5)],
|
|
"UART8_TX" : [(1,0,5)],
|
|
"USART1_RX" : [(2,2,4),(2,5,4)],
|
|
"USART1_TX" : [(2,7,4)],
|
|
"USART2_RX" : [(1,5,4)],
|
|
"USART2_TX" : [(1,6,4)],
|
|
"USART3_RX" : [(1,1,4)],
|
|
"USART3_TX" : [(1,3,4),(1,4,7)],
|
|
"USART6_RX" : [(2,1,5),(2,2,5)],
|
|
"USART6_TX" : [(2,6,5),(2,7,5)],
|
|
}
|
|
|
|
AltFunction_map = {
|
|
# format is PIN:FUNCTION : AFNUM
|
|
# extracted from f732-AF.txt
|
|
"PA0:SAI2_SD_B" : 10,
|
|
"PA0:TIM2_CH1" : 1,
|
|
"PA0:TIM2_ETR" : 1,
|
|
"PA0:TIM5_CH1" : 2,
|
|
"PA0:TIM8_ETR" : 3,
|
|
"PA0:UART4_TX" : 8,
|
|
"PA0:USART2_CTS" : 7,
|
|
"PA1:QUADSPI_BK1_IO3" : 9,
|
|
"PA1:SAI2_MCLK_B" : 10,
|
|
"PA1:TIM2_CH2" : 1,
|
|
"PA1:TIM5_CH2" : 2,
|
|
"PA1:UART4_RX" : 8,
|
|
"PA1:USART2_DE" : 7,
|
|
"PA1:USART2_RTS" : 7,
|
|
"PA2:SAI2_SCK_B" : 8,
|
|
"PA2:TIM2_CH3" : 1,
|
|
"PA2:TIM5_CH3" : 2,
|
|
"PA2:TIM9_CH1" : 3,
|
|
"PA2:USART2_TX" : 7,
|
|
"PA3:TIM2_CH4" : 1,
|
|
"PA3:TIM5_CH4" : 2,
|
|
"PA3:TIM9_CH2" : 3,
|
|
"PA3:USART2_RX" : 7,
|
|
"PA3:OTG_HS_ULPI_D0" : 10,
|
|
"PA4:I2S1_WS" : 5,
|
|
"PA4:I2S3_WS" : 6,
|
|
"PA4:SPI1_NSS" : 5,
|
|
"PA4:SPI3_NSS" : 6,
|
|
"PA4:USART2_CK" : 7,
|
|
"PA4:OTG_HS_SOF" : 12,
|
|
"PA5:I2S1_CK" : 5,
|
|
"PA5:SPI1_SCK" : 5,
|
|
"PA5:TIM2_CH1" : 1,
|
|
"PA5:TIM2_ETR" : 1,
|
|
"PA5:TIM8_CH1N" : 3,
|
|
"PA5:OTG_HS_ULPI_CK" : 10,
|
|
"PA6:SPI1_MISO" : 5,
|
|
"PA6:TIM13_CH1" : 9,
|
|
"PA6:TIM1_BKIN" : 1,
|
|
"PA6:TIM3_CH1" : 2,
|
|
"PA6:TIM8_BKIN" : 3,
|
|
"PA7:I2S1_SD" : 5,
|
|
"PA7:SPI1_MOSI" : 5,
|
|
"PA7:TIM14_CH1" : 9,
|
|
"PA7:TIM1_CH1N" : 1,
|
|
"PA7:TIM3_CH2" : 2,
|
|
"PA7:TIM8_CH1N" : 3,
|
|
"PA8:I2C3_SCL" : 4,
|
|
"PA8:RCC_MCO_1" : 0,
|
|
"PA8:TIM1_CH1" : 1,
|
|
"PA8:TIM8_BKIN2" : 3,
|
|
"PA8:USART1_CK" : 7,
|
|
"PA8:OTG_FS_SOF" : 10,
|
|
"PA9:I2C3_SMBA" : 4,
|
|
"PA9:I2S2_CK" : 5,
|
|
"PA9:SPI2_SCK" : 5,
|
|
"PA9:TIM1_CH2" : 1,
|
|
"PA9:USART1_TX" : 7,
|
|
"PA10:TIM1_CH3" : 1,
|
|
"PA10:USART1_RX" : 7,
|
|
"PA10:OTG_FS_ID" : 10,
|
|
"PA11:CAN1_RX" : 9,
|
|
"PA11:TIM1_CH4" : 1,
|
|
"PA11:USART1_CTS" : 7,
|
|
"PA11:OTG_FS_DM" : 10,
|
|
"PA12:CAN1_TX" : 9,
|
|
"PA12:SAI2_FS_B" : 8,
|
|
"PA12:TIM1_ETR" : 1,
|
|
"PA12:USART1_DE" : 7,
|
|
"PA12:USART1_RTS" : 7,
|
|
"PA12:OTG_FS_DP" : 10,
|
|
"PA13:JTMS-SWDIO" : 0,
|
|
"PA14:JTCK-SWCLK" : 0,
|
|
"PA15:I2S1_WS" : 5,
|
|
"PA15:I2S3_WS" : 6,
|
|
"PA15:SPI1_NSS" : 5,
|
|
"PA15:SPI3_NSS" : 6,
|
|
"PA15:SYS_JTDI" : 0,
|
|
"PA15:TIM2_CH1" : 1,
|
|
"PA15:TIM2_ETR" : 1,
|
|
"PA15:UART4_DE" : 8,
|
|
"PA15:UART4_RTS" : 8,
|
|
"PB0:TIM1_CH2N" : 1,
|
|
"PB0:TIM3_CH3" : 2,
|
|
"PB0:TIM8_CH2N" : 3,
|
|
"PB0:UART4_CTS" : 8,
|
|
"PB0:OTG_HS_ULPI_D1" : 10,
|
|
"PB1:TIM1_CH3N" : 1,
|
|
"PB1:TIM3_CH4" : 2,
|
|
"PB1:TIM8_CH3N" : 3,
|
|
"PB1:OTG_HS_ULPI_D2" : 10,
|
|
"PB2:I2S3_SD" : 7,
|
|
"PB2:QUADSPI_CLK" : 9,
|
|
"PB2:SAI1_SD_A" : 6,
|
|
"PB2:SPI3_MOSI" : 7,
|
|
"PB3:I2S1_CK" : 5,
|
|
"PB3:I2S3_CK" : 6,
|
|
"PB3:SPI1_SCK" : 5,
|
|
"PB3:SPI3_SCK" : 6,
|
|
"PB3:SYS_JTDO-SWO" : 0,
|
|
"PB3:TIM2_CH2" : 1,
|
|
"PB4:I2S2_WS" : 7,
|
|
"PB4:SPI1_MISO" : 5,
|
|
"PB4:SPI2_NSS" : 7,
|
|
"PB4:SPI3_MISO" : 6,
|
|
"PB4:SYS_JTRST" : 0,
|
|
"PB4:TIM3_CH1" : 2,
|
|
"PB5:I2C1_SMBA" : 4,
|
|
"PB5:I2S1_SD" : 5,
|
|
"PB5:I2S3_SD" : 6,
|
|
"PB5:SPI1_MOSI" : 5,
|
|
"PB5:SPI3_MOSI" : 6,
|
|
"PB5:TIM3_CH2" : 2,
|
|
"PB5:OTG_HS_ULPI_D7" : 10,
|
|
"PB6:I2C1_SCL" : 4,
|
|
"PB6:QUADSPI_BK1_NCS" : 10,
|
|
"PB6:TIM4_CH1" : 2,
|
|
"PB6:USART1_TX" : 7,
|
|
"PB7:I2C1_SDA" : 4,
|
|
"PB7:TIM4_CH2" : 2,
|
|
"PB7:USART1_RX" : 7,
|
|
"PB8:CAN1_RX" : 9,
|
|
"PB8:I2C1_SCL" : 4,
|
|
"PB8:SDMMC1_D4" : 12,
|
|
"PB8:TIM10_CH1" : 3,
|
|
"PB8:TIM4_CH3" : 2,
|
|
"PB9:CAN1_TX" : 9,
|
|
"PB9:I2C1_SDA" : 4,
|
|
"PB9:I2S2_WS" : 5,
|
|
"PB9:SDMMC1_D5" : 12,
|
|
"PB9:SPI2_NSS" : 5,
|
|
"PB9:TIM11_CH1" : 3,
|
|
"PB9:TIM4_CH4" : 2,
|
|
"PB10:I2C2_SCL" : 4,
|
|
"PB10:I2S2_CK" : 5,
|
|
"PB10:SPI2_SCK" : 5,
|
|
"PB10:TIM2_CH3" : 1,
|
|
"PB10:USART3_TX" : 7,
|
|
"PB10:OTG_HS_ULPI_D3" : 10,
|
|
"PB11:I2C2_SDA" : 4,
|
|
"PB11:TIM2_CH4" : 1,
|
|
"PB11:USART3_RX" : 7,
|
|
"PB11:OTG_HS_ULPI_D4" : 10,
|
|
"PB12:I2C2_SMBA" : 4,
|
|
"PB12:I2S2_WS" : 5,
|
|
"PB12:SPI2_NSS" : 5,
|
|
"PB12:TIM1_BKIN" : 1,
|
|
"PB12:USART3_CK" : 7,
|
|
"PB12:OTG_HS_ID" : 12,
|
|
"PB12:OTG_HS_ULPI_D5" : 10,
|
|
"PB13:I2S2_CK" : 5,
|
|
"PB13:SPI2_SCK" : 5,
|
|
"PB13:TIM1_CH1N" : 1,
|
|
"PB13:USART3_CTS" : 7,
|
|
"PB13:OTG_HS_ULPI_D6" : 10,
|
|
"PB14:SPI2_MISO" : 5,
|
|
"PB14:TIM12_CH1" : 9,
|
|
"PB14:TIM1_CH2N" : 1,
|
|
"PB14:TIM8_CH2N" : 3,
|
|
"PB14:USART3_DE" : 7,
|
|
"PB14:USART3_RTS" : 7,
|
|
"PB14:OTG_HS_DM" : 12,
|
|
"PB15:I2S2_SD" : 5,
|
|
"PB15:RTC_REFIN" : 0,
|
|
"PB15:SPI2_MOSI" : 5,
|
|
"PB15:TIM12_CH2" : 9,
|
|
"PB15:TIM1_CH3N" : 1,
|
|
"PB15:TIM8_CH3N" : 3,
|
|
"PB15:OTG_HS_DP" : 12,
|
|
"PC0:SAI2_FS_B" : 8,
|
|
"PC0:OTG_HS_ULPI_STP" : 10,
|
|
"PC1:I2S2_SD" : 5,
|
|
"PC1:SAI1_SD_A" : 6,
|
|
"PC1:SPI2_MOSI" : 5,
|
|
"PC1:SYS_TRACED0" : 0,
|
|
"PC2:SPI2_MISO" : 5,
|
|
"PC2:OTG_HS_ULPI_DIR" : 10,
|
|
"PC3:I2S2_SD" : 5,
|
|
"PC3:SPI2_MOSI" : 5,
|
|
"PC3:OTG_HS_ULPI_NXT" : 10,
|
|
"PC4:I2S1_MCK" : 5,
|
|
"PC6:I2S2_MCK" : 5,
|
|
"PC6:SDMMC1_D6" : 12,
|
|
"PC6:TIM3_CH1" : 2,
|
|
"PC6:TIM8_CH1" : 3,
|
|
"PC6:USART6_TX" : 8,
|
|
"PC7:I2S3_MCK" : 6,
|
|
"PC7:SDMMC1_D7" : 12,
|
|
"PC7:TIM3_CH2" : 2,
|
|
"PC7:TIM8_CH2" : 3,
|
|
"PC7:USART6_RX" : 8,
|
|
"PC8:SDMMC1_D0" : 12,
|
|
"PC8:SYS_TRACED1" : 0,
|
|
"PC8:TIM3_CH3" : 2,
|
|
"PC8:TIM8_CH3" : 3,
|
|
"PC8:UART5_DE" : 7,
|
|
"PC8:UART5_RTS" : 7,
|
|
"PC8:USART6_CK" : 8,
|
|
"PC9:I2C3_SDA" : 4,
|
|
"PC9:I2S_CKIN" : 5,
|
|
"PC9:QUADSPI_BK1_IO0" : 9,
|
|
"PC9:RCC_MCO_2" : 0,
|
|
"PC9:SDMMC1_D1" : 12,
|
|
"PC9:TIM3_CH4" : 2,
|
|
"PC9:TIM8_CH4" : 3,
|
|
"PC9:UART5_CTS" : 7,
|
|
"PC10:I2S3_CK" : 6,
|
|
"PC10:QUADSPI_BK1_IO1" : 9,
|
|
"PC10:SDMMC1_D2" : 12,
|
|
"PC10:SPI3_SCK" : 6,
|
|
"PC10:UART4_TX" : 8,
|
|
"PC10:USART3_TX" : 7,
|
|
"PC11:QUADSPI_BK2_NCS" : 9,
|
|
"PC11:SDMMC1_D3" : 12,
|
|
"PC11:SPI3_MISO" : 6,
|
|
"PC11:UART4_RX" : 8,
|
|
"PC11:USART3_RX" : 7,
|
|
"PC12:I2S3_SD" : 6,
|
|
"PC12:SDMMC1_CK" : 12,
|
|
"PC12:SPI3_MOSI" : 6,
|
|
"PC12:SYS_TRACED3" : 0,
|
|
"PC12:UART5_TX" : 8,
|
|
"PC12:USART3_CK" : 7,
|
|
"PD2:SDMMC1_CMD" : 12,
|
|
"PD2:SYS_TRACED2" : 0,
|
|
"PD2:TIM3_ETR" : 2,
|
|
"PD2:UART5_RX" : 8,
|
|
}
|
|
|
|
ADC1_map = {
|
|
# format is PIN : ADC1_CHAN
|
|
"PA1" : 1,
|
|
"PA2" : 2,
|
|
"PA3" : 3,
|
|
"PA4" : 4,
|
|
"PA5" : 5,
|
|
"PA6" : 6,
|
|
"PA7" : 7,
|
|
"PB0" : 8,
|
|
"PB1" : 9,
|
|
"PC0" : 10,
|
|
"PC1" : 11,
|
|
"PC2" : 12,
|
|
"PC3" : 13,
|
|
"PC4" : 14,
|
|
"PC5" : 15,
|
|
}
|