mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: change f303-PWM timers
fixes PWM on channels 3 and 4
This commit is contained in:
parent
adbaccaa08
commit
88d77d0acd
|
@ -26,8 +26,8 @@ I2C_ORDER
|
||||||
# setup for 4 PWM
|
# setup for 4 PWM
|
||||||
PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50)
|
PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50)
|
||||||
PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51)
|
PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51)
|
||||||
PB14 TIM15_CH1 TIM15 PWM(3) GPIO(52)
|
PB14 TIM1_CH2N TIM1 PWM(3) GPIO(52)
|
||||||
PB15 TIM15_CH2 TIM15 PWM(4) GPIO(53)
|
PB15 TIM1_CH3N TIM1 PWM(4) GPIO(53)
|
||||||
|
|
||||||
# enable PWM
|
# enable PWM
|
||||||
define HAL_PERIPH_ENABLE_RC_OUT
|
define HAL_PERIPH_ENABLE_RC_OUT
|
||||||
|
|
Loading…
Reference in New Issue