HAL_ChibiOS: re-arrange KakuteF4 UARTs

this allows for FrSky S.PORT on Telem2, and enables it by default
This commit is contained in:
Andrew Tridgell 2018-11-18 20:50:57 +11:00
parent cfb401995f
commit 39003905b9
1 changed files with 21 additions and 15 deletions

View File

@ -25,9 +25,6 @@ STM32_VDD 330U
# only one I2C bus
I2C_ORDER I2C1
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART1 USART6 UART5
# LEDs
PB5 LED_BLUE OUTPUT LOW GPIO(0)
@ -58,40 +55,49 @@ PC5 ICM20689_DRDY INPUT
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# rcinput is PB11
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
# analog pins
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
# RSSI analog input
PC1 RSSI_ADC_PIN ADC1 SCALE(1)
define BOARD_RSSI_ANA_PIN 11
# define default battery setup
define HAL_BATT_VOLT_PIN 13
define HAL_BATT_CURR_PIN 12
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
# main port, for telem1
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART6 USART1 UART5 USART3
# rcinput is PB11
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
PB10 USART3_TX USART3
# SBUS inversion control pin, active low
PB15 SBUS_INVERT OUTPUT LOW
# for FrSky S.PORT. Has builtin inverters and diode to combine
# RX and TX onto the one pin
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# USART3 for rcinput
#PB10 USART3_TX USART3
#PB11 USART3_RX USART3
PB15 SBUS_INVERT OUTPUT LOW
# default Serial2 to FrSky telemetry
define HAL_SERIAL2_PROTOCOL_DEFAULT 10
# USART6
# USART6, telem1, SERIAL1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# UART4 (GPS)
# UART4 (GPS), SERIAL3
PA1 UART4_RX UART4 NODMA
PA0 UART4_TX UART4 NODMA
# UART5 (ESC sensor)
# UART5 (ESC telemetry sensor), SERIAL4
PD2 UART5_RX UART5
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1