diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4Pro/hwdef.dat index 83cd8c4b49..0dc44d2b7f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk4Pro/hwdef.dat @@ -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