HAL_ChibiOS: enable fmu out 7 and 8 for fmuv5

these are exposed on the Pixhawk4
This commit is contained in:
Andrew Tridgell 2018-06-06 11:28:53 +10:00
parent 2d9df83ed5
commit 63087b6425
2 changed files with 9 additions and 5 deletions

View File

@ -162,8 +162,12 @@ PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
#PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56)
#PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57)
# 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) NODMA
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA
define BOARD_PWM_COUNT_DEFAULT 8
# PWM output for buzzer
PE5 TIM9_CH1 TIM9 GPIO(77) ALARM

View File

@ -774,10 +774,10 @@ def write_PWM_config(f):
for p in pwm_out:
if p.type != t:
continue
chan_str = p.label[7]
chan_str = p.label[-1]
is_complementary = p.label[-1] == 'N';
if not is_int(chan_str):
error("Bad channel for PWM %s" % p)
error("Bad channel for PWM %s chan_str=%s" % (p, chan_str))
chan = int(chan_str)
if chan not in [1, 2, 3, 4]:
error("Bad channel number %u for PWM %s" % (chan, p))
@ -1058,7 +1058,7 @@ def build_peripheral_list():
elif not p.has_extra('ALARM') and not p.has_extra('RCININT'):
# get the TIMn_UP DMA channels for DShot
label = type + '_UP'
if not label in peripherals:
if not label in peripherals and not p.has_extra('NODMA'):
peripherals.append(label)
done.add(type)
return peripherals