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

18 lines
580 B
Plaintext
Raw Permalink Normal View History

# Bi-directional dshot version of CubeOrange
include ../CubeOrangePlus/hwdef.dat
undef PE14 PE13 PE11 PE9 PD13 PD14
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) BIDIR
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) # this will automatically be shared with TIM1_CH4
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) # this will automatically be shared with TIM1_CH1
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR
NODMA I2C*
define STM32_I2C_USE_DMA FALSE
env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm