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

18 lines
504 B
Plaintext

# Bi-directional dshot version of CUAVv5
include ../CUAVv5/hwdef.dat
undef PA10 PE11 PD13 PD14
# This gives bi-dir dshot on the first four channels
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) BIDIR
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR
# On the regular CUAVv5 TIM4_UP cannot be assigned, this just makes it clear
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) NODMA
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) NODMA
DMA_PRIORITY TIM1_CH3 TIM1_CH2 TIM1_UP SDMMC* UART8* ADC* SPI* TIM*
NODMA I2C*
define STM32_I2C_USE_DMA FALSE