AP_HAL_ChibiOS: add toneAlarm support for ChibiOS on MindPX-v2

This commit is contained in:
Mark Whitehorn 2018-02-10 11:16:41 +11:00 committed by Andrew Tridgell
parent 6baad37e47
commit d569e35a0f
2 changed files with 10 additions and 11 deletions

View File

@ -50,7 +50,10 @@ PA4 VDD_5V_SENS ADC1 SCALE(2)
# SPI1 is fram bus # SPI1 is fram bus
PA5 SPI1_SCK SPI1 PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1 PA6 SPI1_MISO SPI1
PA7 TONE INPUT
# Timers 1-4 are used for (servo) PWM outputs and 5/6 are used for clocks
# Use Timer 14 for tone generation
PA7 TIM14_CH1 TIM14 GPIO(32) ALARM
PA8 RUN_LED OUTPUT GPIO(0) PA8 RUN_LED OUTPUT GPIO(0)
PA9 VBUS INPUT PA9 VBUS INPUT

View File

@ -561,14 +561,13 @@ def write_PWM_config(f):
f.write('#define STM32_RCIN_DMA_CHANNEL %u' % dma_chan) f.write('#define STM32_RCIN_DMA_CHANNEL %u' % dma_chan)
f.write('\n') f.write('\n')
if alarm is not None: if alarm is not None:
n_str = alarm.label[3]
if not is_int(n_str):
error("Bad timer number for ALARM PWM %s" % p)
n = int(n_str)
# could probably also use timers 10-14 on STM32
if (n < 1):
error("Bad timer number %u for ALARM PWM %s" % (chan, p))
a = alarm.label.split('_')
chan_str = a[1][2:]
timer_str = a[0][3:]
if not is_int(chan_str) or not is_int(timer_str):
error("Bad timer channel %s" % alarm.label)
n = int(timer_str)
f.write('\n// Alarm PWM output config\n') f.write('\n// Alarm PWM output config\n')
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)
@ -577,9 +576,6 @@ def write_PWM_config(f):
'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED',
'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED' 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED'
] ]
chan_str = alarm.label[7]
if not is_int(chan_str):
error("Bad channel for ALARM PWM %s" % p)
chan = int(chan_str) chan = int(chan_str)
if chan not in [1, 2, 3, 4]: if chan not in [1, 2, 3, 4]:
error("Bad channel number %u for ALARM PWM %s" % (chan, p)) error("Bad channel number %u for ALARM PWM %s" % (chan, p))