ardupilot/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef.dat

28 lines
631 B
Plaintext

include ../MatekL431/hwdef.inc
define HAL_USE_ADC FALSE
define STM32_ADC_USE_ADC1 FALSE
define HAL_DISABLE_ADC_DRIVER TRUE
define HAL_PERIPH_ENABLE_RCIN 1
define AP_PERIPH_RC1_PORT_DEFAULT 2
# Added DMA for RC input
undef PB10
undef PB11
PB10 USART3_TX USART3 SPEED_HIGH
PB11 USART3_RX USART3 SPEED_HIGH
# allow for 4 PWM outputs
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50)
PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51)
PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52)
PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53)
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
# enable ESC control
define HAL_SUPPORT_RCOUT_SERIAL 1
define HAL_WITH_ESC_TELEM 1