HAL_ChibiOS: added ALT(1) configs for more boards
this allows more boards to use the FPort protocol
This commit is contained in:
parent
040a1b7fbe
commit
0d31e614ed
@ -99,9 +99,13 @@ PB10 USART3_TX USART3
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# USART6, RX only for RCIN
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
# RC input defaults to timer capture
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
||||
|
||||
# alternative config using USART for protocols
|
||||
# like FPort
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# UART7 USED BY ESC FROM ORIGINAL DESIGN
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -99,9 +99,13 @@ PB10 USART3_TX USART3
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# USART6, RX only for RCIN
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
# RC input defaults to timer capture
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# alt config to allow RCIN on UART for bi-directional
|
||||
# protocols like FPort
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
|
||||
# UART7, RX only for ESC Telemetry
|
||||
PE7 UART7_RX UART7
|
||||
|
@ -48,7 +48,7 @@ STM32_VDD 330U
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# order of UARTs
|
||||
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
|
||||
UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6 USART2
|
||||
|
||||
#################################################
|
||||
### PIN DEFINITIONS ###
|
||||
@ -57,11 +57,13 @@ UART_ORDER OTG1 USART3 USART1 EMPTY UART4 UART5 USART6
|
||||
PA0 UART4_TX UART4
|
||||
PA1 UART4_RX UART4
|
||||
|
||||
# USART 2 is used for RC Input
|
||||
# PA2 USART2_TX USART2
|
||||
# PA3 USART2_RX USART2
|
||||
# default to timer for RC input
|
||||
PA3 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
|
||||
# alternative using USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
PA4 MPU_CS CS
|
||||
|
||||
# IMU SPI
|
||||
|
@ -28,7 +28,7 @@ STM32_VDD 330U
|
||||
I2C_ORDER I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5
|
||||
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART2
|
||||
|
||||
# LEDs
|
||||
PB9 LED_BLUE OUTPUT LOW GPIO(0)
|
||||
@ -88,12 +88,12 @@ define BOARD_RSSI_ANA_PIN 9
|
||||
PA9 USART1_TX USART1
|
||||
PA10 USART1_RX USART1
|
||||
|
||||
# USART2 (RCIN)
|
||||
#PA2 USART3_TX USART3
|
||||
#PA3 USART3_RX USART3
|
||||
# RC input using timer
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
|
||||
|
||||
# rcinput
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
# alternative RC input using UART
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
# USART3
|
||||
PC10 USART3_TX USART3
|
||||
|
@ -34,7 +34,7 @@ STM32_VDD 330U
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 USART6 USART1 USART3
|
||||
UART_ORDER OTG1 USART6 USART1 USART3 USART2
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
@ -94,8 +94,11 @@ IMU Invensense SPI:mpu6500 ROTATION_YAW_90
|
||||
PA10 USART1_RX USART1
|
||||
PA9 USART1_TX USART1
|
||||
|
||||
# USART2 for RC input, RX only
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
# RC input using timer by default
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
|
||||
|
||||
# alternative RC input using USART2
|
||||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
# USART3
|
||||
PD9 USART3_RX USART3
|
||||
|
@ -36,7 +36,7 @@ FLASH_RESERVE_END_KB 0
|
||||
I2C_ORDER I2C1 I2C2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7
|
||||
UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1 UART7 USART6
|
||||
|
||||
# UART4 is GPS
|
||||
PA0 UART4_TX UART4
|
||||
@ -110,7 +110,12 @@ PC2 BAT_VOLT_SENS ADC1
|
||||
PC3 FMU_ADC1 ADC1
|
||||
PC4 FMU_ADC2 ADC1
|
||||
PC5 FMU_ADC3 ADC1
|
||||
PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC
|
||||
|
||||
# RC input default to timer
|
||||
PC6 TIM8_CH1 TIM8 RCININT PULLDOWN
|
||||
|
||||
# alternative RC input using USART6
|
||||
PC6 USART6_TX USART6 NODMA ALT(1)
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
|
@ -28,7 +28,7 @@ STM32_VDD 330U
|
||||
I2C_ORDER I2C2 I2C1
|
||||
|
||||
# order of UARTs (and USB)
|
||||
UART_ORDER OTG1 UART4 USART3 USART2
|
||||
UART_ORDER OTG1 UART4 USART3 USART2 USART6
|
||||
|
||||
# UART4 serial GPS
|
||||
PA0 UART4_TX UART4
|
||||
@ -74,7 +74,12 @@ PC2 LPS22HB_CS CS
|
||||
PC3 LED_SAFETY OUTPUT
|
||||
PC4 SAFETY_IN INPUT
|
||||
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLUP LOW # also USART6_RX for serial RC
|
||||
# default to RCIN using timer capture
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN
|
||||
|
||||
# alternative using USART6
|
||||
PC7 USART6_RX USART6 NODMA ALT(1)
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
PC10 SDIO_D2 SDIO
|
||||
|
Loading…
Reference in New Issue
Block a user