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

18 lines
445 B
Plaintext

include ../MatekL431/hwdef.inc
define HAL_USE_ADC FALSE
# --------------------- PWM -----------------------
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)
PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54)
define HAL_PERIPH_ENABLE_RC_OUT
# enable APD telemetry on rx1
define HAL_PERIPH_ENABLE_ESC_APD
define APD_ESC_INSTANCES 1
define APD_ESC_SERIAL_0 0