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

39 lines
910 B
Plaintext

include ../MatekL431/hwdef.inc
define HAL_USE_ADC FALSE
undef SERIAL_ORDER
undef USART2 USART2_TX USART2_RX
undef PA2 PA3
SERIAL_ORDER USART1 EMPTY USART3
# --------------------- 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)
# TX2/RX2 -- PWM6/7
PA2 TIM2_CH3 TIM2 PWM(6) GPIO(55)
PA3 TIM2_CH4 TIM2 PWM(7) GPIO(56)
# "curr" pin -- PWM8
PA1 TIM2_CH2 TIM2 PWM(8) GPIO(57)
# "beeper" pin -- PWM9
PA6 TIM16_CH1 TIM16 PWM(9) GPIO(58) NODMA
define HAL_PERIPH_ENABLE_RC_OUT
define HAL_PERIPH_ENABLE_NOTIFY
# enable ESC control
define HAL_SERIAL_ESC_COMM_ENABLED 1
define HAL_SUPPORT_RCOUT_SERIAL 1
define HAL_WITH_ESC_TELEM 1
# also enable relay output via hardpoint msgs
define HAL_PERIPH_ENABLE_RELAY
define AP_RELAY_ENABLED 1