HAL_ChibiOS: updated F745 and OmnibusNanoV6

This commit is contained in:
Andrew Tridgell 2018-08-06 19:27:19 +10:00
parent c249e26a03
commit 2fb84b22c6
3 changed files with 414 additions and 129 deletions

View File

@ -0,0 +1,40 @@
# hw definition file for processing by chibios_pins.py
# for omnibusf4 Nano V6 bootloader
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 133
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
FLASH_SIZE_KB 1024
# don't allow bootloader to use more than 16k
FLASH_USE_MAX_KB 16
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# LEDs
PA8 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
# the location where the bootloader will put the firmware
define FLASH_BOOTLOADER_LOAD_KB 64
# board voltage
STM32_VDD 330U
# order of UARTs
UART_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360

View File

@ -0,0 +1,135 @@
# hw definition file for processing by chibios_pins.py
# Omnibus F4 Nano V6 only
# with F405 mcu, mpu6000 imu, bmp280 barometer, 7456 series osd, no flash log storage
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 133
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# board voltage
STM32_VDD 330U
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 64
# order of I2C buses
I2C_ORDER I2C2
# order of UARTs
UART_ORDER OTG1 USART6 USART1
#adc
PC1 BAT_CURR_SENS ADC1 SCALE(1)
PC2 BAT_VOLT_SENS ADC1 SCALE(1)
PA0 RSSI_IN ADC1
#pwm output
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PB5 TIM3_CH2 TIM3 PWM(4) GPIO(53)
PA4 MPU6000_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# note that this board needs PULLUP on I2C pins
PB10 I2C2_SCL I2C2 PULLUP
PB11 I2C2_SDA I2C2 PULLUP
PB15 SPI2_MOSI SPI2
PB14 SPI2_MISO SPI2
PB13 SPI2_SCK SPI2
PA10 USART1_RX USART1
PA9 USART1_TX USART1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA15 OSD_CS CS
PB3 BMP280_CS CS
PC12 SPI3_MOSI SPI3
PC11 SPI3_MISO SPI3
PC10 SPI3_SCK SPI3
PA8 LED OUTPUT HIGH GPIO(41)
#PB4 TIM3_CH1 TIM3 GPIO(70) ALARM
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC5 VBUS INPUT OPENDRAIN
#LED strip output pad used for RC input
PB6 TIM4_CH1 TIM4 RCININT PULLDOWN LOW
#Omnibus F4 V3 and later had hw inverter on UART6
#Overide it to use as GPS UART port
PC8 SBUS_INVERT_RX OUTPUT LOW
PC9 SBUS_INVERT_TX OUTPUT LOW
# SPI Device table
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ
SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSNANOV6
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_180
define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
define HAL_BARO_BMP280_NAME "bmp280"
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define STORAGE_FLASH_PAGE 1
define HAL_STORAGE_SIZE 15360
# define default battery setup
define HAL_BATT_VOLT_PIN 12
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 18.2
#analog rssi pin (also could be used as analog airspeed input)
#PA0 - ADC123_CH0
define BOARD_RSSI_ANA_PIN 0
define HAL_GPIO_A_LED_PIN 41
define OSD_ENABLED ENABLED
#To complementary channels work we define this
define STM32_PWM_USE_ADVANCED TRUE
define BOARD_PWM_COUNT_DEFAULT 4
#define CH_DBG_ENABLE_ASSERTS TRUE
#define CH_DBG_ENABLE_CHECKS TRUE
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
#define CH_DBG_ENABLE_STACK_CHECK TRUE
#font for the osd
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

View File

@ -135,38 +135,6 @@ AltFunction_map = {
"PA0:TIM8_ETR" : 3,
"PA0:UART4_TX" : 8,
"PA0:USART2_CTS" : 7,
"PA10:DCMI_D1" : 13,
"PA10:EVENTOUT" : 15,
"PA10:OTG_FS_ID" : 10,
"PA10:TIM1_CH3" : 1,
"PA10:USART1_RX" : 7,
"PA11:CAN1_RX" : 9,
"PA11:EVENTOUT" : 15,
"PA11:LCD_R4" : 14,
"PA11:OTG_FS_DM" : 10,
"PA11:TIM1_CH4" : 1,
"PA11:USART1_CTS" : 7,
"PA12:TIM1_ETR" : 1,
"PA12:USART1_RTS" : 7,
"PA12:SAI2_FS_B" : 8,
"PA12:CAN1_TX" : 9,
"PA12:OTG_FS_DP" : 10,
"PA12:LCD_R5" : 14,
"PA12:EVENTOUT" : 15,
"PA13:EVENTOUT" : 15,
"PA13:JTMS-SWDIO" : 0,
"PA14:EVENTOUT" : 15,
"PA14:JTCK-SWCLK" : 0,
"PA15:EVENTOUT" : 15,
"PA15:HDMI-CEC" : 4,
"PA15:I2S1_WS" : 5,
"PA15:I2S3_WS" : 6,
"PA15:JTDI" : 0,
"PA15:SPI1_NSS" : 5,
"PA15:SPI3_NSS" : 6,
"PA15:TIM2_CH1" : 1,
"PA15:TIM2_ETR" : 1,
"PA15:UART4_RTS" : 8,
"PA1:ETH_MII_RX_CLK" : 11,
"PA1:ETH_RMII_REF_CLK" : 11,
"PA1:EVENTOUT" : 15,
@ -243,6 +211,38 @@ AltFunction_map = {
"PA9:SPI2_SCK" : 5,
"PA9:TIM1_CH2" : 1,
"PA9:USART1_TX" : 7,
"PA10:DCMI_D1" : 13,
"PA10:EVENTOUT" : 15,
"PA10:OTG_FS_ID" : 10,
"PA10:TIM1_CH3" : 1,
"PA10:USART1_RX" : 7,
"PA11:CAN1_RX" : 9,
"PA11:EVENTOUT" : 15,
"PA11:LCD_R4" : 14,
"PA11:OTG_FS_DM" : 10,
"PA11:TIM1_CH4" : 1,
"PA11:USART1_CTS" : 7,
"PA12:CAN1_TX" : 9,
"PA12:EVENTOUT" : 15,
"PA12:LCD_R5" : 14,
"PA12:OTG_FS_DP" : 10,
"PA12:SAI2_FS_B" : 8,
"PA12:TIM1_ETR" : 1,
"PA12:USART1_RTS" : 7,
"PA13:EVENTOUT" : 15,
"PA13:JTMS-SWDIO" : 0,
"PA14:EVENTOUT" : 15,
"PA14:JTCK-SWCLK" : 0,
"PA15:EVENTOUT" : 15,
"PA15:HDMI-CEC" : 4,
"PA15:I2S1_WS" : 5,
"PA15:I2S3_WS" : 6,
"PA15:JTDI" : 0,
"PA15:SPI1_NSS" : 5,
"PA15:SPI3_NSS" : 6,
"PA15:TIM2_CH1" : 1,
"PA15:TIM2_ETR" : 1,
"PA15:UART4_RTS" : 8,
"PB0:ETH_MII_RXD2" : 11,
"PB0:EVENTOUT" : 15,
"PB0:LCD_R3" : 9,
@ -381,33 +381,6 @@ AltFunction_map = {
"PC0:LCD_R5" : 14,
"PC0:OTG_HS_ULPI_STP" : 10,
"PC0:SAI2_FS_B" : 8,
"PC10:DCMI_D8" : 13,
"PC10:EVENTOUT" : 15,
"PC10:I2S3_CK" : 6,
"PC10:LCD_R2" : 14,
"PC10:QUADSPI_BK1_IO1" : 9,
"PC10:SDMMC1_D2" : 12,
"PC10:SPI3_SCK" : 6,
"PC10:UART4_TX" : 8,
"PC10:USART3_TX" : 7,
"PC11:DCMI_D4" : 13,
"PC11:EVENTOUT" : 15,
"PC11:QUADSPI_BK2_NCS" : 9,
"PC11:SDMMC1_D3" : 12,
"PC11:SPI3_MISO" : 6,
"PC11:UART4_RX" : 8,
"PC11:USART3_RX" : 7,
"PC12:DCMI_D9" : 13,
"PC12:EVENTOUT" : 15,
"PC12:I2S3_SD" : 6,
"PC12:SDMMC1_CK" : 12,
"PC12:SPI3_MOSI" : 6,
"PC12:TRACED3" : 0,
"PC12:UART5_TX" : 8,
"PC12:USART3_CK" : 7,
"PC13:EVENTOUT" : 15,
"PC14:EVENTOUT" : 15,
"PC15:EVENTOUT" : 15,
"PC1:ETH_MDC" : 11,
"PC1:EVENTOUT" : 15,
"PC1:I2S2_SD" : 5,
@ -425,6 +398,12 @@ AltFunction_map = {
"PC3:I2S2_SD" : 5,
"PC3:OTG_HS_ULPI_NXT" : 10,
"PC3:SPI2_MOSI" : 5,
"PC4:ETH_MII_RXD0" : 11,
"PC4:ETH_RMII_RXD0" : 11,
"PC4:EVENTOUT" : 15,
"PC4:FMC_SDNE0" : 12,
"PC4:I2S1_MCK" : 5,
"PC4:SPDIFRX_IN2" : 8,
"PC5:ETH_MII_RXD1" : 11,
"PC5:ETH_RMII_RXD1" : 11,
"PC5:EVENTOUT" : 15,
@ -464,40 +443,36 @@ AltFunction_map = {
"PC9:TIM3_CH4" : 2,
"PC9:TIM8_CH4" : 3,
"PC9:UART5_CTS" : 7,
"PC10:DCMI_D8" : 13,
"PC10:EVENTOUT" : 15,
"PC10:I2S3_CK" : 6,
"PC10:LCD_R2" : 14,
"PC10:QUADSPI_BK1_IO1" : 9,
"PC10:SDMMC1_D2" : 12,
"PC10:SPI3_SCK" : 6,
"PC10:UART4_TX" : 8,
"PC10:USART3_TX" : 7,
"PC11:DCMI_D4" : 13,
"PC11:EVENTOUT" : 15,
"PC11:QUADSPI_BK2_NCS" : 9,
"PC11:SDMMC1_D3" : 12,
"PC11:SPI3_MISO" : 6,
"PC11:UART4_RX" : 8,
"PC11:USART3_RX" : 7,
"PC12:DCMI_D9" : 13,
"PC12:EVENTOUT" : 15,
"PC12:I2S3_SD" : 6,
"PC12:SDMMC1_CK" : 12,
"PC12:SPI3_MOSI" : 6,
"PC12:TRACED3" : 0,
"PC12:UART5_TX" : 8,
"PC12:USART3_CK" : 7,
"PC13:EVENTOUT" : 15,
"PC14:EVENTOUT" : 15,
"PC15:EVENTOUT" : 15,
"PD0:CAN1_RX" : 9,
"PD0:EVENTOUT" : 15,
"PD0:FMC_D2" : 12,
"PD10:EVENTOUT" : 15,
"PD10:FMC_D15" : 12,
"PD10:LCD_B3" : 14,
"PD10:USART3_CK" : 7,
"PD10:EVENTOUT" : 15,
"PD10:FMC_D15" : 12,
"PD10:LCD_B3" : 14,
"PD10:USART3_CK" : 7,
"PD11:EVENTOUT" : 15,
"PD11:FMC_A16" : 12,
"PD11:FMC_CLE" : 12,
"PD11:I2C4_SMBA" : 4,
"PD11:QUADSPI_BK1_IO0" : 9,
"PD11:SAI2_SD_A" : 10,
"PD11:USART3_CTS" : 7,
"PD12:EVENTOUT" : 15,
"PD12:FMC_A17" : 12,
"PD12:FMC_ALE" : 12,
"PD12:I2C4_SCL" : 4,
"PD12:LPTIM1_IN1" : 3,
"PD12:QUADSPI_BK1_IO1" : 9,
"PD12:SAI2_FS_A" : 10,
"PD12:TIM4_CH1" : 2,
"PD12:USART3_RTS" : 7,
"PD13:EVENTOUT" : 15,
"PD13:FMC_A18" : 12,
"PD13:I2C4_SDA" : 4,
"PD13:LPTIM1_OUT" : 3,
"PD13:QUADSPI_BK1_IO3" : 9,
"PD13:SAI2_SCK_A" : 10,
"PD13:TIM4_CH2" : 2,
"PD1:CAN1_TX" : 9,
"PD1:EVENTOUT" : 15,
"PD1:FMC_D3" : 12,
@ -539,6 +514,41 @@ AltFunction_map = {
"PD9:EVENTOUT" : 15,
"PD9:FMC_D14" : 12,
"PD9:USART3_RX" : 7,
"PD10:EVENTOUT" : 15,
"PD10:FMC_D15" : 12,
"PD10:LCD_B3" : 14,
"PD10:USART3_CK" : 7,
"PD11:EVENTOUT" : 15,
"PD11:FMC_A16" : 12,
"PD11:FMC_CLE" : 12,
"PD11:I2C4_SMBA" : 4,
"PD11:QUADSPI_BK1_IO0" : 9,
"PD11:SAI2_SD_A" : 10,
"PD11:USART3_CTS" : 7,
"PD12:EVENTOUT" : 15,
"PD12:FMC_A17" : 12,
"PD12:FMC_ALE" : 12,
"PD12:I2C4_SCL" : 4,
"PD12:LPTIM1_IN1" : 3,
"PD12:QUADSPI_BK1_IO1" : 9,
"PD12:SAI2_FS_A" : 10,
"PD12:TIM4_CH1" : 2,
"PD12:USART3_RTS" : 7,
"PD13:EVENTOUT" : 15,
"PD13:FMC_A18" : 12,
"PD13:I2C4_SDA" : 4,
"PD13:LPTIM1_OUT" : 3,
"PD13:QUADSPI_BK1_IO3" : 9,
"PD13:SAI2_SCK_A" : 10,
"PD13:TIM4_CH2" : 2,
"PD14:EVENTOUT" : 15,
"PD14:FMC_D0" : 12,
"PD14:TIM4_CH3" : 2,
"PD14:UART8_CTS" : 8,
"PD15:EVENTOUT" : 15,
"PD15:FMC_D1" : 12,
"PD15:TIM4_CH4" : 2,
"PD15:UART8_RTS" : 8,
"PE0:DCMI_D2" : 13,
"PE0:EVENTOUT" : 15,
"PE0:FMC_NBL0" : 12,
@ -546,29 +556,6 @@ AltFunction_map = {
"PE0:SAI2_MCK_A" : 10,
"PE0:TIM4_ETR" : 2,
"PE0:UART8_RX" : 8,
"PE10:EVENTOUT" : 15,
"PE10:FMC_D7" : 12,
"PE10:QUADSPI_BK2_IO3" : 10,
"PE10:TIM1_CH2N" : 1,
"PE10:UART7_CTS" : 8,
"PE11:EVENTOUT" : 15,
"PE11:FMC_D8" : 12,
"PE11:LCD_G3" : 14,
"PE11:SAI2_SD_B" : 10,
"PE11:SPI4_NSS" : 5,
"PE11:TIM1_CH2" : 1,
"PE12:EVENTOUT" : 15,
"PE12:FMC_D9" : 12,
"PE12:LCD_B4" : 14,
"PE12:SAI2_SCK_B" : 10,
"PE12:SPI4_SCK" : 5,
"PE12:TIM1_CH3N" : 1,
"PE13:EVENTOUT" : 15,
"PE13:FMC_D10" : 12,
"PE13:LCD_DE" : 14,
"PE13:SAI2_FS_B" : 10,
"PE13:SPI4_MISO" : 5,
"PE13:TIM1_CH3" : 1,
"PE1:DCMI_D3" : 13,
"PE1:EVENTOUT" : 15,
"PE1:FMC_NBL1" : 12,
@ -625,19 +612,42 @@ AltFunction_map = {
"PE9:QUADSPI_BK2_IO2" : 10,
"PE9:TIM1_CH1" : 1,
"PE9:UART7_RTS" : 8,
"PE10:EVENTOUT" : 15,
"PE10:FMC_D7" : 12,
"PE10:QUADSPI_BK2_IO3" : 10,
"PE10:TIM1_CH2N" : 1,
"PE10:UART7_CTS" : 8,
"PE11:EVENTOUT" : 15,
"PE11:FMC_D8" : 12,
"PE11:LCD_G3" : 14,
"PE11:SAI2_SD_B" : 10,
"PE11:SPI4_NSS" : 5,
"PE11:TIM1_CH2" : 1,
"PE12:EVENTOUT" : 15,
"PE12:FMC_D9" : 12,
"PE12:LCD_B4" : 14,
"PE12:SAI2_SCK_B" : 10,
"PE12:SPI4_SCK" : 5,
"PE12:TIM1_CH3N" : 1,
"PE13:EVENTOUT" : 15,
"PE13:FMC_D10" : 12,
"PE13:LCD_DE" : 14,
"PE13:SAI2_FS_B" : 10,
"PE13:SPI4_MISO" : 5,
"PE13:TIM1_CH3" : 1,
"PE14:EVENTOUT" : 15,
"PE14:FMC_D11" : 12,
"PE14:LCD_CLK" : 14,
"PE14:SAI2_MCK_B" : 10,
"PE14:SPI4_MOSI" : 5,
"PE14:TIM1_CH4" : 1,
"PE15:EVENTOUT" : 15,
"PE15:FMC_D12" : 12,
"PE15:LCD_R7" : 14,
"PE15:TIM1_BKIN" : 1,
"PF0:EVENTOUT" : 15,
"PF0:FMC_A0" : 12,
"PF0:I2C2_SDA" : 4,
"PF10:DCMI_D11" : 13,
"PF10:EVENTOUT" : 15,
"PF10:LCD_DE" : 14,
"PF11:DCMI_D12" : 13,
"PF11:EVENTOUT" : 15,
"PF11:FMC_SDNRAS" : 12,
"PF11:SAI2_SD_B" : 10,
"PF11:SPI5_MOSI" : 5,
"PF12:EVENTOUT" : 15,
"PF12:FMC_A6" : 12,
"PF1:EVENTOUT" : 15,
"PF1:FMC_A1" : 12,
"PF1:I2C2_SCL" : 4,
@ -674,14 +684,27 @@ AltFunction_map = {
"PF9:SPI5_MOSI" : 5,
"PF9:TIM14_CH1" : 9,
"PF9:UART7_CTS" : 8,
"PF10:DCMI_D11" : 13,
"PF10:EVENTOUT" : 15,
"PF10:LCD_DE" : 14,
"PF11:DCMI_D12" : 13,
"PF11:EVENTOUT" : 15,
"PF11:FMC_SDNRAS" : 12,
"PF11:SAI2_SD_B" : 10,
"PF11:SPI5_MOSI" : 5,
"PF12:EVENTOUT" : 15,
"PF12:FMC_A6" : 12,
"PF13:EVENTOUT" : 15,
"PF13:FMC_A7" : 12,
"PF13:I2C4_SMBA" : 4,
"PF14:EVENTOUT" : 15,
"PF14:FMC_A8" : 12,
"PF14:I2C4_SCL" : 4,
"PF15:EVENTOUT" : 15,
"PF15:FMC_A9" : 12,
"PF15:I2C4_SDA" : 4,
"PG0:EVENTOUT" : 15,
"PG0:FMC_A10" : 12,
"PG10:DCMI_D2" : 13,
"PG10:EVENTOUT" : 15,
"PG10:FMC_NE3" : 12,
"PG10:LCD_B2" : 14,
"PG10:LCD_G3" : 9,
"PG10:SAI2_SD_B" : 10,
"PG1:EVENTOUT" : 15,
"PG1:FMC_A11" : 12,
"PG2:EVENTOUT" : 15,
@ -716,6 +739,49 @@ AltFunction_map = {
"PG9:SAI2_FS_B" : 10,
"PG9:SPDIFRX_IN3" : 7,
"PG9:USART6_RX" : 8,
"PG10:DCMI_D2" : 13,
"PG10:EVENTOUT" : 15,
"PG10:FMC_NE3" : 12,
"PG10:LCD_B2" : 14,
"PG10:LCD_G3" : 9,
"PG10:SAI2_SD_B" : 10,
"PG11:DCMI_D3" : 13,
"PG11:ETH_MII_TX_EN" : 11,
"PG11:ETH_RMII_TX_EN" : 11,
"PG11:EVENTOUT" : 15,
"PG11:LCD_B3" : 14,
"PG11:SPDIFRX_IN0" : 7,
"PG12:EVENTOUT" : 15,
"PG12:FMC_NE4" : 12,
"PG12:LCD_B1" : 14,
"PG12:LCD_B4" : 9,
"PG12:LPTIM1_IN1" : 3,
"PG12:SPDIFRX_IN1" : 7,
"PG12:SPI6_MISO" : 5,
"PG12:USART6_RTS" : 8,
"PG13:ETH_MII_TXD0" : 11,
"PG13:ETH_RMII_TXD0" : 11,
"PG13:EVENTOUT" : 15,
"PG13:FMC_A24" : 12,
"PG13:LCD_R0" : 14,
"PG13:LPTIM1_OUT" : 3,
"PG13:SPI6_SCK" : 5,
"PG13:TRACED0" : 0,
"PG13:USART6_CTS" : 8,
"PG14:ETH_MII_TXD1" : 11,
"PG14:ETH_RMII_TXD1" : 11,
"PG14:EVENTOUT" : 15,
"PG14:FMC_A25" : 12,
"PG14:LCD_B0" : 14,
"PG14:LPTIM1_ETR" : 3,
"PG14:QUADSPI_BK2_IO3" : 9,
"PG14:SPI6_MOSI" : 5,
"PG14:TRACED1" : 0,
"PG14:USART6_TX" : 8,
"PG15:DCMI_D13" : 13,
"PG15:EVENTOUT" : 15,
"PG15:FMC_SDNCAS" : 12,
"PG15:USART6_CTS" : 8,
"PH0:EVENTOUT" : 15,
"PH1:EVENTOUT" : 15,
"PH2:ETH_MII_CRS" : 11,
@ -751,6 +817,50 @@ AltFunction_map = {
"PH7:FMC_SDCKE1" : 12,
"PH7:I2C3_SCL" : 4,
"PH7:SPI5_MISO" : 5,
"PH8:DCMI_HSYNC" : 13,
"PH8:EVENTOUT" : 15,
"PH8:FMC_D16" : 12,
"PH8:I2C3_SDA" : 4,
"PH8:LCD_R2" : 14,
"PH9:DCMI_D0" : 13,
"PH9:EVENTOUT" : 15,
"PH9:FMC_D17" : 12,
"PH9:I2C3_SMBA" : 4,
"PH9:LCD_R3" : 14,
"PH9:TIM12_CH2" : 9,
"PH10:DCMI_D1" : 13,
"PH10:EVENTOUT" : 15,
"PH10:FMC_D18" : 12,
"PH10:I2C4_SMBA" : 4,
"PH10:LCD_R4" : 14,
"PH10:TIM5_CH1" : 2,
"PH11:DCMI_D2" : 13,
"PH11:EVENTOUT" : 15,
"PH11:FMC_D19" : 12,
"PH11:I2C4_SCL" : 4,
"PH11:LCD_R5" : 14,
"PH11:TIM5_CH2" : 2,
"PH12:DCMI_D3" : 13,
"PH12:EVENTOUT" : 15,
"PH12:FMC_D20" : 12,
"PH12:I2C4_SDA" : 4,
"PH12:LCD_R6" : 14,
"PH12:TIM5_CH3" : 2,
"PH13:CAN1_TX" : 9,
"PH13:EVENTOUT" : 15,
"PH13:FMC_D21" : 12,
"PH13:LCD_G2" : 14,
"PH13:TIM8_CH1N" : 3,
"PH14:DCMI_D4" : 13,
"PH14:EVENTOUT" : 15,
"PH14:FMC_D22" : 12,
"PH14:LCD_G3" : 14,
"PH14:TIM8_CH2N" : 3,
"PH15:DCMI_D11" : 13,
"PH15:EVENTOUT" : 15,
"PH15:FMC_D23" : 12,
"PH15:LCD_G4" : 14,
"PH15:TIM8_CH3N" : 3,
}
ADC1_map = {