mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed DMA on TIM12 for Pixhawk4Pro
This commit is contained in:
parent
dd835f5fce
commit
4e067ee3cd
|
@ -173,8 +173,8 @@ PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
|
|||
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
|
||||
# we need to disable DMA on the last 2 FMU channels
|
||||
# as timer 12 doesn't have a TIMn_UP DMA option
|
||||
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56)
|
||||
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57)
|
||||
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA
|
||||
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
||||
|
|
Loading…
Reference in New Issue