HAL_ChibiOS: changed RCIN to PULLDOWN

this fixes a high cpu load with no receiver connected
This commit is contained in:
Andrew Tridgell 2018-02-07 18:40:13 +11:00
parent 86189393a7
commit 4548fd4d2f
3 changed files with 3 additions and 3 deletions

View File

@ -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 PULLUP LOW DMA_CH0 # also USART6_RX for serial RC
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0 # also USART6_RX for serial RC
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO

View File

@ -96,7 +96,7 @@ PC2 BAT_VOLT_SENS ADC1
PC3 FMU_ADC1 ADC1
PC4 FMU_ADC2 ADC1
PC5 FMU_ADC3 ADC1
PC6 TIM8_CH1 TIM8 RCIN PULLUP LOW DMA_CH0 # also USART6_RX for serial RC
PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW DMA_CH0 # also USART6_RX for serial RC
PC7 TIM3_CH2 TIM3 PWM(10) GPIO(51)
PC8 SDIO_D0 SDIO

View File

@ -32,7 +32,7 @@ I2C_ORDER I2C1
UART_ORDER OTG1 USART6 USART3
# we need to add support for N channels for RCIN
# PB14 TIM8_CH2 TIM8 RCIN PULLUP LOW DMA_CH0
# PB14 TIM8_CH2 TIM8 RCIN PULLDOWN LOW DMA_CH0
# analog pins
PC3 VDD_5V_SENS ADC1