|
|
@ -24,7 +24,7 @@ FLASH_SIZE_KB 1024 |
|
|
|
I2C_ORDER I2C2 I2C1 |
|
|
|
I2C_ORDER I2C2 I2C1 |
|
|
|
|
|
|
|
|
|
|
|
# order of UARTs (and USB) |
|
|
|
# order of UARTs (and USB) |
|
|
|
SERIAL_ORDER OTG1 USART3 USART2 UART4 USART6 |
|
|
|
SERIAL_ORDER OTG1 USART3 USART2 UART4 |
|
|
|
|
|
|
|
|
|
|
|
# UART4 serial GPS |
|
|
|
# UART4 serial GPS |
|
|
|
PA0 UART4_TX UART4 |
|
|
|
PA0 UART4_TX UART4 |
|
|
@ -73,8 +73,6 @@ PC4 SAFETY_IN INPUT |
|
|
|
# default to RCIN using timer capture |
|
|
|
# default to RCIN using timer capture |
|
|
|
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN |
|
|
|
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN |
|
|
|
|
|
|
|
|
|
|
|
# alternative using USART6 |
|
|
|
|
|
|
|
PC7 USART6_RX USART6 NODMA ALT(1) |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
PC8 SDIO_D0 SDIO |
|
|
|
PC8 SDIO_D0 SDIO |
|
|
|
PC9 SDIO_D1 SDIO |
|
|
|
PC9 SDIO_D1 SDIO |
|
|
|