ardupilot/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-bdshot/hwdef.dat

20 lines
545 B
Plaintext
Raw Normal View History

# Bi-directional dshot version of KakuteH7
include ../KakuteH7/hwdef.dat
undef PB0 PB1 PB3 PB10 PC7
# Must use USART6 for RCIN rather than RCINT as timer needed for bi-dir dshot
PC7 USART6_RX USART6 NODMA
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
define DEFAULT_SERIAL6_BAUD 115
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_ESCTelemetry
define DEFAULT_SERIAL7_BAUD 115
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
PB3 TIM2_CH2 TIM2 PWM(3) GPIO(52) BIDIR
PB10 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR