mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: adjust RCIN pin settings for fmuv4
thanks to Mark for this change
This commit is contained in:
parent
9301e4888a
commit
10f940c8d0
|
@ -51,7 +51,7 @@ PA13 JTMS-SWDIO SWD
|
|||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# PA15 ALARM
|
||||
PB0 TIM3_CH3 TIM3 PPMIN # RC Input PPM
|
||||
PB0 INPUT PULLUP # RC Input PPM
|
||||
PB1 LED_GREEN OUTPUT GPIO(0)
|
||||
PB2 BOOT1 INPUT
|
||||
PB3 LED_BLUE OUTPUT GPIO(1)
|
||||
|
@ -88,7 +88,7 @@ PC2 MPU9250_CS CS
|
|||
PC3 LED_SAFETY OUTPUT
|
||||
PC4 SAFETY_IN INPUT
|
||||
PC5 VDD_PERIPH_EN OUTPUT HIGH
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0 # also USART6_RX for serial RC
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW DMA_CH0 # also USART6_RX for serial RC
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
|
|
Loading…
Reference in New Issue