mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_ChibiOS: fixed hwdef.h generation for PWM on tim12
This commit is contained in:
parent
63087b6425
commit
c05086430d
@ -755,7 +755,7 @@ def write_PWM_config(f):
|
|||||||
|
|
||||||
f.write('// PWM timer config\n')
|
f.write('// PWM timer config\n')
|
||||||
for t in sorted(pwm_timers):
|
for t in sorted(pwm_timers):
|
||||||
n = int(t[3])
|
n = int(t[3:])
|
||||||
f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
|
f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
|
||||||
f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
|
f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
|
||||||
f.write('\n')
|
f.write('\n')
|
||||||
@ -763,7 +763,7 @@ def write_PWM_config(f):
|
|||||||
groups = []
|
groups = []
|
||||||
for t in sorted(pwm_timers):
|
for t in sorted(pwm_timers):
|
||||||
group = len(groups) + 1
|
group = len(groups) + 1
|
||||||
n = int(t[3])
|
n = int(t[3:])
|
||||||
chan_list = [255, 255, 255, 255]
|
chan_list = [255, 255, 255, 255]
|
||||||
chan_mode = [
|
chan_mode = [
|
||||||
'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED',
|
'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED',
|
||||||
|
Loading…
Reference in New Issue
Block a user