mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: allow frsky invert for p3pro and mindpx-v2
This commit is contained in:
parent
f0c13d4089
commit
b346d82f96
|
@ -74,7 +74,6 @@ PE15 MAG_CS CS
|
|||
PH5 EEPROM_CS CS
|
||||
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
PA10 FRSKY_INV OUTPUT GPIO(78)
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA11 OTG_FS_DM OTG1
|
||||
|
@ -172,6 +171,11 @@ PD15 MPU9250_DRDY INPUT
|
|||
# UART8 serial4 FrSky
|
||||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
# allow this uart to be inverted for transmit under user control
|
||||
# the polarity is the value to use on the GPIO to change the polarity
|
||||
# to the opposite of the default
|
||||
PA10 UART8_TXINV OUTPUT HIGH GPIO(78) POL(0)
|
||||
|
||||
PE3 VDD_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
|
|
|
@ -99,8 +99,6 @@ PB9 I2C1_SDA I2C1
|
|||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
PB12 FRSKY_INV OUTPUT
|
||||
|
||||
# SPI2 is external SPI (radio NRF)
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
|
@ -146,6 +144,11 @@ PD11 ACCEL_MAG_CS CS
|
|||
PE0 UART8_RX UART8
|
||||
PE1 UART8_TX UART8
|
||||
|
||||
# allow this uart to be inverted for transmit under user control
|
||||
# the polarity is the value to use on the GPIO to change the polarity
|
||||
# to the opposite of the default
|
||||
PB12 UART8_TXINV OUTPUT HIGH GPIO(78) POL(0)
|
||||
|
||||
# SPI4 is M_SPI (main sensors)
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE3 MPU_CS CS
|
||||
|
|
Loading…
Reference in New Issue