mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed spektrum RC input on Pixracer
RCININT is inverted compared to RCIN, so need to enable SBUS_INV pin
This commit is contained in:
parent
d0cdaf17e4
commit
f3066c978d
|
@ -104,7 +104,9 @@ PC2 MPU9250_CS CS
|
|||
PC3 LED_SAFETY OUTPUT
|
||||
PC4 SAFETY_IN INPUT PULLDOWN
|
||||
PC5 VDD_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW # also USART6_RX for serial RC
|
||||
PC13 SBUS_INV OUTPUT LOW
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
|
@ -112,7 +114,7 @@ PC10 SDIO_D2 SDIO
|
|||
PC11 SDIO_D3 SDIO
|
||||
PC12 SDIO_CK SDIO
|
||||
|
||||
PC13 SBUS_INV OUTPUT
|
||||
|
||||
PC14 20608_DRDY INPUT
|
||||
PC15 20608_CS CS
|
||||
|
||||
|
|
Loading…
Reference in New Issue