HAL_ChibiOS: fixed dma resolver for H7
This commit is contained in:
parent
07e2167996
commit
acf77ba49a
@ -27,6 +27,20 @@ mcu = {
|
||||
'DTCM_RAM_SIZE_KB' : 128,
|
||||
}
|
||||
|
||||
pincount = {
|
||||
'A': 16,
|
||||
'B': 16,
|
||||
'C': 16,
|
||||
'D': 16,
|
||||
'E': 16,
|
||||
'F': 16,
|
||||
'G': 16,
|
||||
'H': 16,
|
||||
'I': 16,
|
||||
'J': 0,
|
||||
'K': 0
|
||||
}
|
||||
|
||||
# no DMA map as we will dynamically allocate DMA channels using the DMAMUX
|
||||
DMA_Map = None
|
||||
|
||||
@ -134,7 +148,7 @@ AltFunction_map = {
|
||||
"PA8:USART1_CK" : 7,
|
||||
"PA9:DCMI_D0" : 13,
|
||||
"PA9:EVENT-OUT" : 15,
|
||||
"PA9:FDCAN1_RXFD_MODE" : 9,
|
||||
"PA9:CAN1_RX" : 9,
|
||||
"PA9:HRTIM_CHC1" : 2,
|
||||
"PA9:I2C3_SMBA" : 4,
|
||||
"PA9:I2S2_CK" : 5,
|
||||
@ -145,7 +159,7 @@ AltFunction_map = {
|
||||
"PA9:USART1_TX" : 7,
|
||||
"PA10:DCMI_D1" : 13,
|
||||
"PA10:EVENT-OUT" : 15,
|
||||
"PA10:FDCAN1_TXFD_MODE" : 9,
|
||||
"PA10:CAN1_TX" : 9,
|
||||
"PA10:HRTIM_CHC2" : 2,
|
||||
"PA10:LCD_B1" : 14,
|
||||
"PA10:LCD_B4" : 12,
|
||||
@ -155,7 +169,7 @@ AltFunction_map = {
|
||||
"PA10:TIM1_CH3" : 1,
|
||||
"PA10:USART1_RX" : 7,
|
||||
"PA11:EVENT-OUT" : 15,
|
||||
"PA11:FDCAN1_RX" : 9,
|
||||
"PA11:CAN1_RX" : 9,
|
||||
"PA11:HRTIM_CHD1" : 2,
|
||||
"PA11:I2S2_WS" : 5,
|
||||
"PA11:LCD_R4" : 14,
|
||||
@ -166,7 +180,7 @@ AltFunction_map = {
|
||||
"PA11:UART4_RX" : 6,
|
||||
"PA11:USART1_CTS_NSS" : 7,
|
||||
"PA12:EVENT-OUT" : 15,
|
||||
"PA12:FDCAN1_TX" : 9,
|
||||
"PA12:CAN1_TX" : 9,
|
||||
"PA12:HRTIM_CHD2" : 2,
|
||||
"PA12:I2S2_CK" : 5,
|
||||
"PA12:LCD_R5" : 14,
|
||||
@ -251,7 +265,7 @@ AltFunction_map = {
|
||||
"PB5:DCMI_D10" : 13,
|
||||
"PB5:ETH_PPS_OUT" : 11,
|
||||
"PB5:EVENT-OUT" : 15,
|
||||
"PB5:FDCAN2_RX" : 9,
|
||||
"PB5:CAN2_RX" : 9,
|
||||
"PB5:FMC_SDCKE1" : 12,
|
||||
"PB5:HRTIM_EEV7" : 3,
|
||||
"PB5:I2C1_SMBA" : 4,
|
||||
@ -268,7 +282,7 @@ AltFunction_map = {
|
||||
"PB6:DCMI_D5" : 13,
|
||||
"PB6:DFSDM_DATIN5" : 11,
|
||||
"PB6:EVENT-OUT" : 15,
|
||||
"PB6:FDCAN2_TX" : 9,
|
||||
"PB6:CAN2_TX" : 9,
|
||||
"PB6:FMC_SDNE1" : 12,
|
||||
"PB6:HDMI_CEC" : 5,
|
||||
"PB6:HRTIM_EEV8" : 3,
|
||||
@ -283,7 +297,7 @@ AltFunction_map = {
|
||||
"PB7:DCMI_VSYNC" : 13,
|
||||
"PB7:DFSDM_CKIN5" : 11,
|
||||
"PB7:EVENT-OUT" : 15,
|
||||
"PB7:FDCAN2_TXFD_MODE" : 9,
|
||||
"PB7:CAN2_TX" : 9,
|
||||
"PB7:FMC_NL" : 12,
|
||||
"PB7:HRTIM_EEV9" : 3,
|
||||
"PB7:I2C1_SDA" : 4,
|
||||
@ -296,7 +310,7 @@ AltFunction_map = {
|
||||
"PB8:DFSDM_CKIN7" : 3,
|
||||
"PB8:ETH_MII_TXD3" : 11,
|
||||
"PB8:EVENT-OUT" : 15,
|
||||
"PB8:FDCAN1_RX" : 9,
|
||||
"PB8:CAN1_RX" : 9,
|
||||
"PB8:I2C1_SCL" : 4,
|
||||
"PB8:I2C4_SCL" : 6,
|
||||
"PB8:LCD_B6" : 14,
|
||||
@ -309,7 +323,7 @@ AltFunction_map = {
|
||||
"PB9:DCMI_D7" : 13,
|
||||
"PB9:DFSDM_DATIN7" : 3,
|
||||
"PB9:EVENT-OUT" : 15,
|
||||
"PB9:FDCAN1_TX" : 9,
|
||||
"PB9:CAN1_TX" : 9,
|
||||
"PB9:I2C1_SDA" : 4,
|
||||
"PB9:I2C4_SDA" : 6,
|
||||
"PB9:I2C4_SMBA" : 11,
|
||||
@ -350,7 +364,7 @@ AltFunction_map = {
|
||||
"PB12:ETH_MII_TXD0" : 11,
|
||||
"PB12:ETH_RMII_TXD0" : 11,
|
||||
"PB12:EVENT-OUT" : 15,
|
||||
"PB12:FDCAN2_RX" : 9,
|
||||
"PB12:CAN2_RX" : 9,
|
||||
"PB12:I2C2_SMBA" : 4,
|
||||
"PB12:I2S2_WS" : 5,
|
||||
"PB12:OTG_HS_ID" : 12,
|
||||
@ -364,7 +378,7 @@ AltFunction_map = {
|
||||
"PB13:ETH_MII_TXD1" : 11,
|
||||
"PB13:ETH_RMII_TXD1" : 11,
|
||||
"PB13:EVENT-OUT" : 15,
|
||||
"PB13:FDCAN2_TX" : 9,
|
||||
"PB13:CAN2_TX" : 9,
|
||||
"PB13:I2S2_CK" : 5,
|
||||
"PB13:LPTIM2_OUT" : 3,
|
||||
"PB13:OTG_HS_ULPI_D6" : 10,
|
||||
@ -535,14 +549,14 @@ AltFunction_map = {
|
||||
"PC15:EVENT-OUT" : 15,
|
||||
"PD0:DFSDM_CKIN6" : 3,
|
||||
"PD0:EVENT-OUT" : 15,
|
||||
"PD0:FDCAN1_RX" : 9,
|
||||
"PD0:CAN1_RX" : 9,
|
||||
"PD0:FMC_D2" : 12,
|
||||
"PD0:FMC_DA2" : 12,
|
||||
"PD0:SAI3_SCK_A" : 6,
|
||||
"PD0:UART4_RX" : 8,
|
||||
"PD1:DFSDM_DATIN6" : 3,
|
||||
"PD1:EVENT-OUT" : 15,
|
||||
"PD1:FDCAN1_TX" : 9,
|
||||
"PD1:CAN1_TX" : 9,
|
||||
"PD1:FMC_D3" : 12,
|
||||
"PD1:FMC_DA3" : 12,
|
||||
"PD1:SAI3_SD_A" : 6,
|
||||
@ -560,15 +574,15 @@ AltFunction_map = {
|
||||
"PD3:I2S2_CK" : 5,
|
||||
"PD3:LCD_G7" : 14,
|
||||
"PD3:SPI2_SCK" : 5,
|
||||
"PD3:USART2_CTS_NSS" : 7,
|
||||
"PD3:USART2_CTS" : 7,
|
||||
"PD4:EVENT-OUT" : 15,
|
||||
"PD4:FDCAN1_RXFD_MODE" : 9,
|
||||
"PD4:CAN1_RX" : 9,
|
||||
"PD4:FMC_NOE" : 12,
|
||||
"PD4:HRTIM_FLT3" : 2,
|
||||
"PD4:SAI3_FS_A" : 6,
|
||||
"PD4:USART2_RTS" : 7,
|
||||
"PD5:EVENT-OUT" : 15,
|
||||
"PD5:FDCAN1_TXFD_MODE" : 9,
|
||||
"PD5:CAN1_TX" : 9,
|
||||
"PD5:FMC_NWE" : 12,
|
||||
"PD5:HRTIM_EEV3" : 2,
|
||||
"PD5:USART2_TX" : 7,
|
||||
@ -576,7 +590,7 @@ AltFunction_map = {
|
||||
"PD6:DFSDM_CKIN4" : 3,
|
||||
"PD6:DFSDM_DATIN1" : 4,
|
||||
"PD6:EVENT-OUT" : 15,
|
||||
"PD6:FDCAN2_RXFD_MODE" : 9,
|
||||
"PD6:CAN2_RX" : 9,
|
||||
"PD6:FMC_NWAIT" : 12,
|
||||
"PD6:I2S3_SDO" : 5,
|
||||
"PD6:LCD_B2" : 14,
|
||||
@ -605,14 +619,14 @@ AltFunction_map = {
|
||||
"PD8:USART3_TX" : 7,
|
||||
"PD9:DFSDM_DATIN3" : 3,
|
||||
"PD9:EVENT-OUT" : 15,
|
||||
"PD9:FDCAN2_RXFD_MODE" : 9,
|
||||
"PD9:CAN2_RX" : 9,
|
||||
"PD9:FMC_D14" : 12,
|
||||
"PD9:FMC_DA14" : 12,
|
||||
"PD9:SAI3_SD_B" : 6,
|
||||
"PD9:USART3_RX" : 7,
|
||||
"PD10:DFSDM_CKOUT" : 3,
|
||||
"PD10:EVENT-OUT" : 15,
|
||||
"PD10:FDCAN2_TXFD_MODE" : 9,
|
||||
"PD10:CAN2_TX" : 9,
|
||||
"PD10:FMC_D15" : 12,
|
||||
"PD10:FMC_DA15" : 12,
|
||||
"PD10:LCD_B3" : 14,
|
||||
@ -624,7 +638,7 @@ AltFunction_map = {
|
||||
"PD11:LPTIM2_IN2" : 3,
|
||||
"PD11:QUADSPI_BK1_IO0" : 9,
|
||||
"PD11:SAI2_SD_A" : 10,
|
||||
"PD11:USART3_CTS_NSS" : 7,
|
||||
"PD11:USART3_CTS" : 7,
|
||||
"PD12:EVENT-OUT" : 15,
|
||||
"PD12:FMC_A17" : 12,
|
||||
"PD12:I2C4_SCL" : 4,
|
||||
@ -655,7 +669,7 @@ AltFunction_map = {
|
||||
"PD15:UART8_RTS" : 8,
|
||||
"PE0:DCMI_D2" : 13,
|
||||
"PE0:EVENT-OUT" : 15,
|
||||
"PE0:FDCAN1_RXFD_MODE" : 9,
|
||||
"PE0:CAN1_RX" : 9,
|
||||
"PE0:FMC_NBL0" : 12,
|
||||
"PE0:HRTIM_SCIN" : 3,
|
||||
"PE0:LPTIM1_ETR" : 1,
|
||||
@ -665,7 +679,7 @@ AltFunction_map = {
|
||||
"PE0:UART8_RX" : 8,
|
||||
"PE1:DCMI_D3" : 13,
|
||||
"PE1:EVENT-OUT" : 15,
|
||||
"PE1:FDCAN1_TXFD_MODE" : 9,
|
||||
"PE1:CAN1_TX" : 9,
|
||||
"PE1:FMC_NBL1" : 12,
|
||||
"PE1:HRTIM_SCOUT" : 3,
|
||||
"PE1:LPTIM1_IN2" : 1,
|
||||
@ -955,7 +969,7 @@ AltFunction_map = {
|
||||
"PG13:LPTIM1_OUT" : 1,
|
||||
"PG13:SPI6_SCK" : 5,
|
||||
"PG13:TRACED0" : 0,
|
||||
"PG13:USART6_CTS_NSS" : 7,
|
||||
"PG13:USART6_CTS" : 7,
|
||||
"PG14:ETH_MII_TXD1" : 11,
|
||||
"PG14:ETH_RMII_TXD1" : 11,
|
||||
"PG14:EVENT-OUT" : 15,
|
||||
@ -969,7 +983,7 @@ AltFunction_map = {
|
||||
"PG15:DCMI_D13" : 13,
|
||||
"PG15:EVENT-OUT" : 15,
|
||||
"PG15:FMC_SDNCAS" : 12,
|
||||
"PG15:USART6_CTS_NSS" : 7,
|
||||
"PG15:USART6_CTS" : 7,
|
||||
"PH0:EVENT-OUT" : 15,
|
||||
"PH1:EVENT-OUT" : 15,
|
||||
"PH2:ETH_MII_CRS" : 11,
|
||||
@ -1038,24 +1052,178 @@ AltFunction_map = {
|
||||
"PH12:LCD_R6" : 14,
|
||||
"PH12:TIM5_CH3" : 2,
|
||||
"PH13:EVENT-OUT" : 15,
|
||||
"PH13:FDCAN1_TX" : 9,
|
||||
"PH13:CAN1_TX" : 9,
|
||||
"PH13:FMC_D21" : 12,
|
||||
"PH13:LCD_G2" : 14,
|
||||
"PH13:TIM8_CH1N" : 3,
|
||||
"PH13:UART4_TX" : 8,
|
||||
"PH14:DCMI_D4" : 13,
|
||||
"PH14:EVENT-OUT" : 15,
|
||||
"PH14:FDCAN1_RX" : 9,
|
||||
"PH14:CAN1_RX" : 9,
|
||||
"PH14:FMC_D22" : 12,
|
||||
"PH14:LCD_G3" : 14,
|
||||
"PH14:TIM8_UCH2N" : 3,
|
||||
"PH14:UART4_RX" : 8,
|
||||
"PH15:DCMI_D11" : 13,
|
||||
"PH15:EVENT-OUT" : 15,
|
||||
"PH15:FDCAN1_TXFD_MODE" : 9,
|
||||
"PH15:CAN1_TX" : 9,
|
||||
"PH15:FMC_D23" : 12,
|
||||
"PH15:LCD_G4" : 14,
|
||||
"PH15:TIM8_CH3N" : 3,
|
||||
"PI0:DCMI_D13" : 13,
|
||||
"PI0:EVENT-OUT" : 15,
|
||||
"PI0:CAN1_RX" : 9,
|
||||
"PI0:FMC_D24" : 12,
|
||||
"PI0:I2S2_WS" : 5,
|
||||
"PI0:LCD_G5" : 14,
|
||||
"PI0:SPI2_NSS" : 5,
|
||||
"PI0:TIM5_CH4" : 2,
|
||||
"PI1:DCMI_D8" : 13,
|
||||
"PI1:EVENT-OUT" : 15,
|
||||
"PI1:FMC_D25" : 12,
|
||||
"PI1:I2S2_CK" : 5,
|
||||
"PI1:LCD_G6" : 14,
|
||||
"PI1:SPI2_SCK" : 5,
|
||||
"PI1:TIM8_BKIN2" : 3,
|
||||
"PI1:TIM8_BKIN2_COMP12" : 11,
|
||||
"PI2:DCMI_D9" : 13,
|
||||
"PI2:EVENT-OUT" : 15,
|
||||
"PI2:FMC_D26" : 12,
|
||||
"PI2:I2S2_SDI" : 5,
|
||||
"PI2:LCD_G7" : 14,
|
||||
"PI2:SPI2_MISO" : 5,
|
||||
"PI2:TIM8_CH4" : 3,
|
||||
"PI3:DCMI_D10" : 13,
|
||||
"PI3:EVENT-OUT" : 15,
|
||||
"PI3:FMC_D27" : 12,
|
||||
"PI3:I2S2_SDO" : 5,
|
||||
"PI3:SPI2_MOSI" : 5,
|
||||
"PI3:TIM8_ETR" : 3,
|
||||
"PI4:DCMI_D5" : 13,
|
||||
"PI4:EVENT-OUT" : 15,
|
||||
"PI4:FMC_NBL2" : 12,
|
||||
"PI4:LCD_B4" : 14,
|
||||
"PI4:SAI2_MCK_A" : 10,
|
||||
"PI4:TIM8_BKIN" : 3,
|
||||
"PI4:TIM8_BKIN_COMP12" : 11,
|
||||
"PI5:DCMI_VSYNC" : 13,
|
||||
"PI5:EVENT-OUT" : 15,
|
||||
"PI5:FMC_NBL3" : 12,
|
||||
"PI5:LCD_B5" : 14,
|
||||
"PI5:SAI2_SCK_A" : 10,
|
||||
"PI5:TIM8_CH1" : 3,
|
||||
"PI6:DCMI_D6" : 13,
|
||||
"PI6:EVENT-OUT" : 15,
|
||||
"PI6:FMC_D28" : 12,
|
||||
"PI6:LCD_B6" : 14,
|
||||
"PI6:SAI2_SD_A" : 10,
|
||||
"PI6:TIM8_CH2" : 3,
|
||||
"PI7:DCMI_D7" : 13,
|
||||
"PI7:EVENT-OUT" : 15,
|
||||
"PI7:FMC_D29" : 12,
|
||||
"PI7:LCD_B7" : 14,
|
||||
"PI7:SAI2_FS_A" : 10,
|
||||
"PI7:TIM8_CH3" : 3,
|
||||
"PI8:EVENT-OUT" : 15,
|
||||
"PI9:EVENT-OUT" : 15,
|
||||
"PI9:CAN1_RX" : 9,
|
||||
"PI9:FMC_D30" : 12,
|
||||
"PI9:LCD_VSYNC" : 14,
|
||||
"PI9:UART4_RX" : 8,
|
||||
"PI10:ETH_MII_RX_ER" : 11,
|
||||
"PI10:EVENT-OUT" : 15,
|
||||
"PI10:CAN1_RX" : 9,
|
||||
"PI10:FMC_D31" : 12,
|
||||
"PI10:LCD_HSYNC" : 14,
|
||||
"PI11:EVENT-OUT" : 15,
|
||||
"PI11:LCD_G6" : 9,
|
||||
"PI11:OTG_HS_ULPI_DIR" : 10,
|
||||
"PI12:EVENT-OUT" : 15,
|
||||
"PI12:LCD_HSYNC" : 14,
|
||||
"PI13:EVENT-OUT" : 15,
|
||||
"PI13:LCD_VSYNC" : 14,
|
||||
"PI14:EVENT-OUT" : 15,
|
||||
"PI14:LCD_CLK" : 14,
|
||||
"PI15:EVENT-OUT" : 15,
|
||||
"PI15:LCD_G2" : 9,
|
||||
"PI15:LCD_R0" : 14,
|
||||
"PJ0:EVENT-OUT" : 15,
|
||||
"PJ0:LCD_R1" : 14,
|
||||
"PJ0:LCD_R7" : 9,
|
||||
"PJ1:EVENT-OUT" : 15,
|
||||
"PJ1:LCD_R2" : 14,
|
||||
"PJ2:EVENT-OUT" : 15,
|
||||
"PJ2:LCD_R3" : 14,
|
||||
"PJ3:EVENT-OUT" : 15,
|
||||
"PJ3:LCD_R4" : 14,
|
||||
"PJ4:EVENT-OUT" : 15,
|
||||
"PJ4:LCD_R5" : 14,
|
||||
"PJ5:EVENT-OUT" : 15,
|
||||
"PJ5:LCD_R6" : 14,
|
||||
"PJ6:EVENT-OUT" : 15,
|
||||
"PJ6:LCD_R7" : 14,
|
||||
"PJ6:TIM8_CH2" : 3,
|
||||
"PJ7:EVENT-OUT" : 15,
|
||||
"PJ7:LCD_G0" : 14,
|
||||
"PJ7:TIM8_CH2N" : 3,
|
||||
"PJ7:TRGIN" : 0,
|
||||
"PJ8:EVENT-OUT" : 15,
|
||||
"PJ8:LCD_G1" : 14,
|
||||
"PJ8:TIM1_CH3N" : 1,
|
||||
"PJ8:TIM8_CH1" : 3,
|
||||
"PJ8:UART8_TX" : 8,
|
||||
"PJ9:EVENT-OUT" : 15,
|
||||
"PJ9:LCD_G2" : 14,
|
||||
"PJ9:TIM1_CH3" : 1,
|
||||
"PJ9:TIM8_CH1N" : 3,
|
||||
"PJ9:UART8_RX" : 8,
|
||||
"PJ10:EVENT-OUT" : 15,
|
||||
"PJ10:LCD_G3" : 14,
|
||||
"PJ10:SPI5_MOSI" : 5,
|
||||
"PJ10:TIM1_CH2N" : 1,
|
||||
"PJ10:TIM8_CH2" : 3,
|
||||
"PJ11:EVENT-OUT" : 15,
|
||||
"PJ11:LCD_G4" : 14,
|
||||
"PJ11:SPI5_MISO" : 5,
|
||||
"PJ11:TIM1_CH2" : 1,
|
||||
"PJ11:TIM8_CH2N" : 3,
|
||||
"PJ12:EVENT-OUT" : 15,
|
||||
"PJ12:LCD_B0" : 14,
|
||||
"PJ12:LCD_G3" : 9,
|
||||
"PJ12:TRGOUT" : 0,
|
||||
"PJ13:EVENT-OUT" : 15,
|
||||
"PJ13:LCD_B1" : 14,
|
||||
"PJ13:LCD_B4" : 9,
|
||||
"PJ14:EVENT-OUT" : 15,
|
||||
"PJ14:LCD_B2" : 14,
|
||||
"PJ15:EVENT-OUT" : 15,
|
||||
"PJ15:LCD_B3" : 14,
|
||||
"PK0:EVENT-OUT" : 15,
|
||||
"PK0:LCD_G5" : 14,
|
||||
"PK0:SPI5_SCK" : 5,
|
||||
"PK0:TIM1_CH1N" : 1,
|
||||
"PK0:TIM8_CH3" : 3,
|
||||
"PK1:EVENT-OUT" : 15,
|
||||
"PK1:LCD_G6" : 14,
|
||||
"PK1:SPI5_NSS" : 5,
|
||||
"PK1:TIM1_CH1" : 1,
|
||||
"PK1:TIM8_CH3N" : 3,
|
||||
"PK2:EVENT-OUT" : 15,
|
||||
"PK2:LCD_G7" : 14,
|
||||
"PK2:TIM1_BKIN" : 1,
|
||||
"PK2:TIM1_BKIN_COMP12" : 11,
|
||||
"PK2:TIM8_BKIN" : 3,
|
||||
"PK2:TIM8_BKIN_COMP12" : 10,
|
||||
"PK3:EVENT-OUT" : 15,
|
||||
"PK3:LCD_B4" : 14,
|
||||
"PK4:EVENT-OUT" : 15,
|
||||
"PK4:LCD_B5" : 14,
|
||||
"PK5:EVENT-OUT" : 15,
|
||||
"PK5:LCD_B6" : 14,
|
||||
"PK6:EVENT-OUT" : 15,
|
||||
"PK6:LCD_B7" : 14,
|
||||
"PK7:EVENT-OUT" : 15,
|
||||
"PK7:LCD_DE" : 14,
|
||||
}
|
||||
|
||||
ADC1_map = {
|
||||
|
@ -15,7 +15,7 @@ def is_pin(str):
|
||||
return False
|
||||
if str[0] != 'P':
|
||||
return False
|
||||
if str[1] not in "ABCDEFGH":
|
||||
if str[1] not in "ABCDEFGHIJK":
|
||||
return False
|
||||
try:
|
||||
p = int(str[2:])
|
||||
|
@ -860,7 +860,11 @@ def write_UART_config_bootloader(f):
|
||||
have_uart = True
|
||||
f.write('#define BOOTLOADER_DEV_LIST %s\n' % ','.join(devlist))
|
||||
if not have_uart:
|
||||
f.write('#define HAL_USE_SERIAL FALSE\n')
|
||||
f.write('''
|
||||
#ifndef HAL_USE_SERIAL
|
||||
#define HAL_USE_SERIAL FALSE
|
||||
#endif
|
||||
''')
|
||||
|
||||
def write_I2C_config(f):
|
||||
'''write I2C config defines'''
|
||||
@ -1040,11 +1044,11 @@ def write_PWM_config(f):
|
||||
advanced_timer = 'false'
|
||||
pwm_clock = 1000000
|
||||
period = 20000 * pwm_clock / 1000000
|
||||
f.write('''#ifdef STM32_TIM_TIM%u_UP_DMA_STREAM
|
||||
f.write('''#if defined(STM32_TIM_TIM%u_UP_DMA_STREAM) && defined(STM32_TIM_TIM%u_UP_DMA_CHAN)
|
||||
# define HAL_PWM%u_DMA_CONFIG true, STM32_TIM_TIM%u_UP_DMA_STREAM, STM32_TIM_TIM%u_UP_DMA_CHAN
|
||||
#else
|
||||
# define HAL_PWM%u_DMA_CONFIG false, 0, 0
|
||||
#endif\n''' % (n, n, n, n, n))
|
||||
#endif\n''' % (n, n, n, n, n, n))
|
||||
f.write('''#define HAL_PWM_GROUP%u { %s, \\
|
||||
{%u, %u, %u, %u}, \\
|
||||
/* Group Initial Config */ \\
|
||||
|
@ -121,6 +121,10 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
continue
|
||||
assigned = False
|
||||
check_list = []
|
||||
if dma_map is None:
|
||||
curr_dict[periph] = "STM32_DMA_STREAM_ID_ANY"
|
||||
assigned = True
|
||||
continue
|
||||
if not periph in dma_map:
|
||||
print("Unknown peripheral function %s in DMA map for %s" %
|
||||
(periph, mcu_type))
|
||||
@ -176,9 +180,14 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
shared = ''
|
||||
if len(stream_assign[stream]) > 1:
|
||||
shared = ' // shared %s' % ','.join(stream_assign[stream])
|
||||
f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" %
|
||||
(chibios_dma_define_name(key)+'STREAM', curr_dict[key][0],
|
||||
curr_dict[key][1], shared))
|
||||
if curr_dict[key] == "STM32_DMA_STREAM_ID_ANY":
|
||||
f.write("#define %-30s STM32_DMA_STREAM_ID_ANY\n" % (chibios_dma_define_name(key)+'STREAM'))
|
||||
f.write("#define %-30s 0U\n" % (chibios_dma_define_name(key)+'CHAN'))
|
||||
continue
|
||||
else:
|
||||
f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" %
|
||||
(chibios_dma_define_name(key)+'STREAM', curr_dict[key][0],
|
||||
curr_dict[key][1], shared))
|
||||
for streamchan in dma_map[key]:
|
||||
if stream == (streamchan[0], streamchan[1]):
|
||||
f.write("#define %-30s %u\n" %
|
||||
@ -199,18 +208,25 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
key = 'UART%u' % u
|
||||
if key is None:
|
||||
continue
|
||||
if dma_map is None:
|
||||
dma_rx_chn = "0"
|
||||
dma_tx_chn = "0"
|
||||
else:
|
||||
dma_rx_chn = "STM32_%s_RX_DMA_CHN" % key
|
||||
dma_tx_chn = "STM32_%s_TX_DMA_CHN" % key
|
||||
|
||||
f.write("#define STM32_%s_RX_DMA_CONFIG " % key)
|
||||
if key + "_RX" in curr_dict:
|
||||
f.write(
|
||||
"true, STM32_UART_%s_RX_DMA_STREAM, STM32_%s_RX_DMA_CHN\n" %
|
||||
(key, key))
|
||||
"true, STM32_UART_%s_RX_DMA_STREAM, %s\n" %
|
||||
(key, dma_rx_chn))
|
||||
else:
|
||||
f.write("false, 0, 0\n")
|
||||
f.write("#define STM32_%s_TX_DMA_CONFIG " % key)
|
||||
if key + "_TX" in curr_dict:
|
||||
f.write(
|
||||
"true, STM32_UART_%s_TX_DMA_STREAM, STM32_%s_TX_DMA_CHN\n" %
|
||||
(key, key))
|
||||
"true, STM32_UART_%s_TX_DMA_STREAM, %s\n" %
|
||||
(key, dma_tx_chn))
|
||||
else:
|
||||
f.write("false, 0, 0\n")
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user