From b0badf8cafa3ccc8f025e60ed5eb5639baffbf6a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 Aug 2018 10:53:12 +1000 Subject: [PATCH] HAL_ChibiOS: fixes for F745 builds --- .../AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat | 15 +- .../hwdef/scripts/STM32F745xx.py | 368 ++++++++++++------ 2 files changed, 250 insertions(+), 133 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index 3c1798e087..e8e0561788 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -85,12 +85,12 @@ PD5 USART2_TX USART2 PD6 USART2_RX USART2 # USART3 (GPS) -PB11 USART3_RX USART3 -PB10 USART3_TX USART3 +PB11 USART3_RX USART3 NODMA +PB10 USART3_TX USART3 NODMA # UART4 (GPS2) -PA0 UART4_TX UART4 -PA1 UART4_RX UART4 +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA # UART6, RX only, for RCIN PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW @@ -102,6 +102,13 @@ PB0 TIM3_CH3 TIM3 PWM(1) PB1 TIM3_CH4 TIM3 PWM(2) PE9 TIM1_CH1 TIM1 PWM(3) PE11 TIM1_CH2 TIM1 PWM(4) +PC9 TIM8_CH4 TIM8 PWM(5) +PA3 TIM5_CH4 TIM5 PWM(6) + +PD15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 DMA_PRIORITY S* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py index 06e77a6642..ec47cca401 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/STM32F745xx.py @@ -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 = {