mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: change RCIN FLOAT to PULLDOWN
this lowers the chance of noise on a RCIN pin causing incorrect protocol detection
This commit is contained in:
parent
495ec52a00
commit
47da7f5c9b
|
@ -43,7 +43,7 @@ PA2 USART2_TX USART2
|
|||
PA3 USART2_RX USART2
|
||||
|
||||
# UART3RX (RCInput)
|
||||
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
PB11 TIM2_CH4 TIM2 RCININT PULLDOWN LOW
|
||||
PA8 SBUS_INVERT_RX OUTPUT
|
||||
|
||||
# UART4 (user), only TX pinned out
|
||||
|
|
|
@ -71,7 +71,7 @@ define HAL_BATT_CURR_SCALE 17.0
|
|||
SERIAL_ORDER OTG1 USART6 USART1 UART4 UART5 USART3
|
||||
|
||||
# rcinput is PB11
|
||||
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
|
||||
PB11 TIM2_CH4 TIM2 RCININT PULLDOWN LOW
|
||||
PB10 USART3_TX USART3
|
||||
|
||||
# SBUS inversion control pin, active high
|
||||
|
|
|
@ -98,7 +98,7 @@ PA2 USART2_TX USART2 NODMA
|
|||
PA3 USART2_RX USART2 NODMA ALT(1)
|
||||
|
||||
# default to timer for RC input
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW
|
||||
|
||||
# USART3
|
||||
PC10 USART3_TX USART3
|
||||
|
|
|
@ -53,7 +53,7 @@ PA0 UART4_TX UART4
|
|||
PA1 UART4_RX UART4
|
||||
|
||||
# default to timer for RC input
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW
|
||||
|
||||
# alternative using USART2
|
||||
PA2 USART2_TX USART2 NODMA
|
||||
|
|
|
@ -116,7 +116,7 @@ PD0 UART4_RX UART4 NODMA
|
|||
PB8 UART5_RX UART5 NODMA
|
||||
|
||||
# USART6 (RC input), SERIAL7
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# as an alternative config setup the RX6 pin as a uart. This allows
|
||||
|
|
|
@ -119,7 +119,7 @@ PB9 UART4_TX UART4
|
|||
PB8 UART4_RX UART4
|
||||
|
||||
# USART6 (RC input), SERIAL7
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
|
||||
# as an alternative config setup the RX6 pin as a uart. This allows
|
||||
|
|
|
@ -115,7 +115,7 @@ PA0 UART4_TX UART4
|
|||
PA1 UART4_RX UART4
|
||||
|
||||
# USART6, RX only for RCIN
|
||||
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN LOW
|
||||
PC6 USART6_TX USART6 NODMA LOW
|
||||
|
||||
# UART7 USED BY ESC FROM ORIGINAL DESIGN
|
||||
|
|
|
@ -103,7 +103,7 @@ 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
|
||||
PC7 TIM8_CH2 TIM8 RCININT PULLDOWN LOW # also USART6_RX for serial RC
|
||||
PC13 SBUS_INV OUTPUT LOW
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
|
|
|
@ -74,7 +74,7 @@ STDOUT_BAUDRATE 57600
|
|||
#PC4
|
||||
PC5 LED_GREEN OUTPUT GPIO(25)
|
||||
#PC6
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC8 RELAY_1 OUTPUT LOW GPIO(33)
|
||||
PC9 RELAY_2 OUTPUT LOW GPIO(34)
|
||||
PC10 SPI3_SCK SPI3
|
||||
|
|
|
@ -74,7 +74,7 @@ STDOUT_BAUDRATE 57600
|
|||
#PC4
|
||||
PC5 LED_GREEN OUTPUT GPIO(25)
|
||||
#PC6
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC8 RELAY_1 OUTPUT LOW GPIO(33)
|
||||
PC9 RELAY_2 OUTPUT LOW GPIO(34)
|
||||
PC10 SPI3_SCK SPI3
|
||||
|
|
|
@ -75,7 +75,7 @@ STDOUT_BAUDRATE 57600
|
|||
#PC4
|
||||
PC5 LED_GREEN OUTPUT GPIO(25)
|
||||
#PC6
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC8 RELAY_1 OUTPUT LOW GPIO(33)
|
||||
PC9 RELAY_2 OUTPUT LOW GPIO(34)
|
||||
PC10 SPI3_SCK SPI3
|
||||
|
|
|
@ -74,7 +74,7 @@ STDOUT_BAUDRATE 57600
|
|||
#PC4
|
||||
PC5 LED_GREEN OUTPUT GPIO(25)
|
||||
#PC6
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC8 RELAY_1 OUTPUT LOW GPIO(33)
|
||||
PC9 RELAY_2 OUTPUT LOW GPIO(34)
|
||||
PC10 SPI3_SCK SPI3
|
||||
|
|
|
@ -74,7 +74,7 @@ STDOUT_BAUDRATE 57600
|
|||
#PC4
|
||||
PC5 LED_GREEN OUTPUT GPIO(25)
|
||||
#PC6
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC8 RELAY_1 OUTPUT LOW GPIO(33)
|
||||
PC9 RELAY_2 OUTPUT LOW GPIO(34)
|
||||
PC10 SPI3_SCK SPI3
|
||||
|
|
|
@ -77,7 +77,7 @@ PA10 USART1_RX USART1 SPEED_HIGH
|
|||
PC13 SPEKTRUM_PWR_EN OUTPUT LOW
|
||||
define HAL_GPIO_PIN_SPEKTRUM_OUT PAL_LINE(GPIOA,10U)
|
||||
|
||||
PA8 RCIN INPUT SPEED_HIGH FLOATING # RC Input PPM
|
||||
PA8 RCIN INPUT SPEED_HIGH PULLDOWN # RC Input PPM
|
||||
|
||||
# analog inputs
|
||||
PA4 VSERVO ADC1
|
||||
|
|
|
@ -75,7 +75,7 @@ PB15 SPI2_MOSI SPI2
|
|||
PC0 VBUS_VALID INPUT
|
||||
PC4 SAFETY_IN INPUT PULLDOWN
|
||||
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW # also USART6_RX for serial RC
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW # also USART6_RX for serial RC
|
||||
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
|
|
|
@ -90,7 +90,7 @@ PC15 BMI088_GYRO_CS CS
|
|||
PC3 LED_SAFETY OUTPUT
|
||||
PC4 SAFETY_IN INPUT PULLDOWN
|
||||
PC5 VDD_PERIPH_EN OUTPUT HIGH
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW # also USART6_RX for serial RC
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW # also USART6_RX for serial RC
|
||||
|
||||
# Now setup the pins for the microSD card, if available.
|
||||
PC8 SDMMC1_D0 SDMMC1
|
||||
|
|
|
@ -39,7 +39,7 @@ define HAL_STORAGE_SIZE 32768
|
|||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# RC Input set for Interrupt not DMA
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# also USART6_RX for serial RC
|
||||
|
||||
|
|
|
@ -49,7 +49,7 @@ define STORAGE_FLASH_PAGE 1
|
|||
USB_STRING_MANUFACTURER "mRo"
|
||||
|
||||
# RC Input set for Interrupt not DMA also USART6_RX for serial RC
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# Control of Spektrum power pin
|
||||
PE4 SPEKTRUM_PWR OUTPUT LOW GPIO(70)
|
||||
|
|
|
@ -37,7 +37,7 @@ define HAL_STORAGE_SIZE 32768
|
|||
USB_STRING_MANUFACTURER "mRo"
|
||||
|
||||
# RC Input set for Interrupt not DMA
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# GPIO(70) # also USART6_RX for serial RC
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@ define HAL_STORAGE_SIZE 32768
|
|||
USB_STRING_MANUFACTURER "mRo"
|
||||
|
||||
# RC Input set for Interrupt not DMA
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# GPIO(70) # also USART6_RX for serial RC
|
||||
|
||||
|
|
|
@ -43,7 +43,7 @@ define HAL_WITH_RAMTRON 1
|
|||
USB_STRING_MANUFACTURER "mRo"
|
||||
|
||||
# RC Input set for Interrupt also USART6_RX for serial RC
|
||||
PC7 TIM3_CH2 TIM3 RCININT FLOAT LOW
|
||||
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
|
||||
|
||||
# Control of Spektrum power pin
|
||||
PE4 SPEKTRUM_PWR OUTPUT LOW GPIO(70)
|
||||
|
|
|
@ -27,7 +27,7 @@ SERIAL_ORDER OTG1 USART1 EMPTY USART3
|
|||
|
||||
# rcinput is PC6, which is the 3rd "PWM IN" pin (the yellow wire on a
|
||||
# revolution board)
|
||||
PC6 TIM8_CH1 TIM8 RCIN FLOAT LOW
|
||||
PC6 TIM8_CH1 TIM8 RCIN PULLDOWN LOW
|
||||
|
||||
# analog pins
|
||||
PC3 VDD_5V_SENS ADC1
|
||||
|
|
|
@ -57,7 +57,7 @@ PB11 USART3_RX USART3
|
|||
|
||||
# -------RCIN-------------
|
||||
# Soft Serial for serial RC & PPM
|
||||
PC7 TIM8_CH2 TIM8 RCIN FLOAT LOW
|
||||
PC7 TIM8_CH2 TIM8 RCIN PULLDOWN LOW
|
||||
PC6 SBUS_INVERT OUTPUT
|
||||
|
||||
# -------ADC-------------
|
||||
|
|
|
@ -83,7 +83,7 @@ PA10 USART1_RX USART1
|
|||
#PA3 USART3_RX USART3
|
||||
|
||||
# rcinput
|
||||
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
||||
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW
|
||||
|
||||
# USART3
|
||||
PC10 USART3_TX USART3
|
||||
|
|
Loading…
Reference in New Issue