HAL_ChibiOS: auto-configure timer channels
allow for one marked PPMIN for input
This commit is contained in:
parent
d65ec2ada7
commit
daa9eec836
@ -30,7 +30,9 @@ using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
void ChibiRCInput::init()
|
||||
{
|
||||
#if HAL_USE_ICU == TRUE
|
||||
ppm_init(1000000, true);
|
||||
#endif
|
||||
chMtxObjectInit(&rcin_mutex);
|
||||
_init = true;
|
||||
}
|
||||
@ -164,12 +166,14 @@ void ChibiRCInput::_timer_tick(void)
|
||||
if (!_init) {
|
||||
return;
|
||||
}
|
||||
#if HAL_USE_ICU == TRUE
|
||||
if (ppm_available()) {
|
||||
chMtxLock(&rcin_mutex);
|
||||
_num_channels = ppm_read_bulk(_rc_values, RC_INPUT_MAX_CHANNELS);
|
||||
_rcin_timestamp_last_signal = AP_HAL::micros();
|
||||
chMtxUnlock(&rcin_mutex);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef HAL_RCINPUT_WITH_AP_RADIO
|
||||
if (radio && radio->last_recv_us() != last_radio_us) {
|
||||
|
@ -18,10 +18,6 @@
|
||||
|
||||
#include "hwdef.h"
|
||||
|
||||
#ifndef PPM_ICU_TIMER
|
||||
#define PPM_ICU_TIMER ICUD4
|
||||
#endif
|
||||
|
||||
#ifndef PPM_ICU_CHANNEL
|
||||
#define PPM_ICU_CHANNEL ICU_CHANNEL_2
|
||||
#endif
|
||||
|
@ -104,7 +104,7 @@
|
||||
* @brief Enables the ICU subsystem.
|
||||
*/
|
||||
#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
|
||||
#define HAL_USE_ICU TRUE
|
||||
#define HAL_USE_ICU FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -160,7 +160,7 @@
|
||||
* @brief Enables the SERIAL over USB subsystem.
|
||||
*/
|
||||
#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
|
||||
#define HAL_USE_SERIAL_USB TRUE
|
||||
#define HAL_USE_SERIAL_USB FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -181,7 +181,7 @@
|
||||
* @brief Enables the USB subsystem.
|
||||
*/
|
||||
#if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
|
||||
#define HAL_USE_USB TRUE
|
||||
#define HAL_USE_USB FALSE
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -54,19 +54,47 @@
|
||||
* HAL driver system settings.
|
||||
*/
|
||||
#define STM32_NO_INIT FALSE
|
||||
|
||||
#ifndef STM32_HSI_ENABLED
|
||||
#define STM32_HSI_ENABLED TRUE
|
||||
#endif
|
||||
|
||||
#ifndef STM32_LSI_ENABLED
|
||||
#define STM32_LSI_ENABLED TRUE
|
||||
#endif
|
||||
|
||||
#ifndef STM32_HSE_ENABLED
|
||||
#define STM32_HSE_ENABLED TRUE
|
||||
#endif
|
||||
|
||||
#ifndef STM32_LSE_ENABLED
|
||||
#define STM32_LSE_ENABLED FALSE
|
||||
#endif
|
||||
|
||||
#ifndef STM32_CLOCK48_REQUIRED
|
||||
#define STM32_CLOCK48_REQUIRED TRUE
|
||||
#endif
|
||||
|
||||
#ifndef STM32_SW
|
||||
#define STM32_SW STM32_SW_PLL
|
||||
#endif
|
||||
|
||||
#ifndef STM32_PLLSRC
|
||||
#define STM32_PLLSRC STM32_PLLSRC_HSE
|
||||
#endif
|
||||
#ifndef STM32_PLLM_VALUE
|
||||
#define STM32_PLLM_VALUE 24
|
||||
#endif
|
||||
#ifndef STM32_PLLN_VALUE
|
||||
#define STM32_PLLN_VALUE 336
|
||||
#endif
|
||||
#ifndef STM32_PLLP_VALUE
|
||||
#define STM32_PLLP_VALUE 2
|
||||
#endif
|
||||
#ifndef STM32_PLLQ_VALUE
|
||||
#define STM32_PLLQ_VALUE 7
|
||||
#endif
|
||||
|
||||
#define STM32_HPRE STM32_HPRE_DIV1
|
||||
#define STM32_PPRE1 STM32_PPRE1_DIV4
|
||||
#define STM32_PPRE2 STM32_PPRE2_DIV2
|
||||
@ -187,13 +215,6 @@
|
||||
/*
|
||||
* ICU driver system settings.
|
||||
*/
|
||||
#define STM32_ICU_USE_TIM1 FALSE
|
||||
#define STM32_ICU_USE_TIM2 FALSE
|
||||
#define STM32_ICU_USE_TIM3 FALSE
|
||||
#define STM32_ICU_USE_TIM4 TRUE
|
||||
#define STM32_ICU_USE_TIM5 FALSE
|
||||
#define STM32_ICU_USE_TIM8 FALSE
|
||||
#define STM32_ICU_USE_TIM9 FALSE
|
||||
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
|
||||
@ -217,13 +238,6 @@
|
||||
* PWM driver system settings.
|
||||
*/
|
||||
#define STM32_PWM_USE_ADVANCED FALSE
|
||||
#define STM32_PWM_USE_TIM1 TRUE
|
||||
#define STM32_PWM_USE_TIM2 FALSE
|
||||
#define STM32_PWM_USE_TIM3 FALSE
|
||||
#define STM32_PWM_USE_TIM4 FALSE
|
||||
#define STM32_PWM_USE_TIM5 FALSE
|
||||
#define STM32_PWM_USE_TIM8 FALSE
|
||||
#define STM32_PWM_USE_TIM9 FALSE
|
||||
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
|
||||
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
|
||||
@ -293,8 +307,6 @@
|
||||
/*
|
||||
* USB driver system settings.
|
||||
*/
|
||||
#define STM32_USB_USE_OTG1 TRUE
|
||||
#define STM32_USB_USE_OTG2 FALSE
|
||||
#define STM32_USB_OTG1_IRQ_PRIORITY 14
|
||||
#define STM32_USB_OTG2_IRQ_PRIORITY 14
|
||||
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
|
||||
|
@ -16,6 +16,8 @@
|
||||
|
||||
#include "ppm.h"
|
||||
|
||||
#if HAL_USE_ICU
|
||||
|
||||
static ICUConfig icucfg; //Input Capture Unit Config
|
||||
static uint16_t ppm_buffer[10] = {0};
|
||||
static bool updated[10] = {0};
|
||||
@ -43,9 +45,9 @@ bool ppm_init(uint32_t freq, bool active_high)
|
||||
icucfg.overflow_cb = NULL;
|
||||
icucfg.dier = 0;
|
||||
|
||||
icuStart(&PPM_ICU_TIMER, &icucfg);
|
||||
icuStartCapture(&PPM_ICU_TIMER);
|
||||
icuEnableNotifications(&PPM_ICU_TIMER);
|
||||
icuStart(&HAL_ICU_TIMER, &icucfg);
|
||||
icuStartCapture(&HAL_ICU_TIMER);
|
||||
icuEnableNotifications(&HAL_ICU_TIMER);
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -99,3 +101,4 @@ static void ppm_measurement_cb(ICUDriver *icup)
|
||||
buf_ptr++;
|
||||
}
|
||||
}
|
||||
#endif // HAL_USE_ICU
|
||||
|
@ -53,7 +53,7 @@ PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# PA15 ALARM
|
||||
PB0 RCINPUT INPUT
|
||||
PB0 TIM3_CH3 TIM3 PPMIN # RC Input PPM
|
||||
PB1 LED_GREEN OUTPUT
|
||||
PB2 BOOT1 INPUT
|
||||
PB3 LED_BLUE OUTPUT
|
||||
|
@ -39,6 +39,9 @@ spidev = []
|
||||
# SPI bus list
|
||||
spi_list = []
|
||||
|
||||
# all config lines in order
|
||||
alllines = []
|
||||
|
||||
mcu_type = None
|
||||
|
||||
def is_int(str):
|
||||
@ -222,6 +225,7 @@ def process_line(line):
|
||||
'''process one line of pin definition file'''
|
||||
a = shlex.split(line)
|
||||
# keep all config lines for later use
|
||||
alllines.append(line)
|
||||
config[a[0]] = a[1:]
|
||||
if a[0] == 'MCU':
|
||||
global mcu_type
|
||||
@ -270,10 +274,18 @@ def write_mcu_config(f):
|
||||
f.write('#define USE_POSIX\n\n')
|
||||
if not 'SDIO_CMD' in bylabel:
|
||||
f.write('#define HAL_USE_SDC FALSE\n')
|
||||
if 'OTG1' in bytype:
|
||||
f.write('#define STM32_USB_USE_OTG1 TRUE\n')
|
||||
f.write('#define HAL_USE_USB TRUE\n')
|
||||
f.write('#define HAL_USE_SERIAL_USB TRUE\n')
|
||||
if 'OTG2' in bytype:
|
||||
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
|
||||
# write any custom STM32 defines
|
||||
for d in config.keys():
|
||||
for d in alllines:
|
||||
if d.startswith('STM32_'):
|
||||
f.write('#define %s %s\n' % (d, ' '.join(config[d])))
|
||||
f.write('#define %s\n' % d)
|
||||
if d.startswith('define '):
|
||||
f.write('#define %s\n' % d[7:])
|
||||
f.write('\n')
|
||||
|
||||
def write_USB_config(f):
|
||||
@ -410,6 +422,36 @@ def write_I2C_config(f):
|
||||
f.write('#define HAL_I2C%u_CONFIG { &I2CD%u, STM32_I2C_I2C%u_TX_DMA_STREAM, STM32_I2C_I2C%u_RX_DMA_STREAM }\n' % (n, n, n, n))
|
||||
f.write('#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
|
||||
def write_PWM_config(f):
|
||||
'''write PWM config defines'''
|
||||
ppm_in = None
|
||||
pwm_out = []
|
||||
pwm_timers = []
|
||||
for l in bylabel.keys():
|
||||
p = bylabel[l]
|
||||
if p.type.startswith('TIM'):
|
||||
if p.has_extra('PPMIN'):
|
||||
ppm_in = p
|
||||
else:
|
||||
pwm_out.append(p)
|
||||
if p.type not in pwm_timers:
|
||||
pwm_timers.append(p.type)
|
||||
if ppm_in is not None:
|
||||
chan = int(ppm_in.label[7:])
|
||||
n = int(ppm_in.type[3])
|
||||
f.write('// PPM input config\n')
|
||||
f.write('#define HAL_USE_ICU TRUE\n')
|
||||
f.write('#define HAL_ICU_TIMER ICUD%u\n' % n)
|
||||
f.write('#define STM32_ICU_USE_TIM%u TRUE\n' % n)
|
||||
f.write('#define HAL_ICU_CHANNEL ICU_CHANNEL_%u\n' % chan)
|
||||
f.write('\n')
|
||||
f.write('// PWM output config\n')
|
||||
for t in sorted(pwm_timers):
|
||||
n = int(t[3])
|
||||
f.write('#define STM32_PWM_USE_TIM%u TRUE\n' % n)
|
||||
f.write('\n')
|
||||
|
||||
|
||||
|
||||
def write_prototype_file():
|
||||
'''write the prototype file for apj generation'''
|
||||
@ -459,6 +501,7 @@ def write_hwdef_header(outfilename):
|
||||
write_USB_config(f)
|
||||
write_I2C_config(f)
|
||||
write_SPI_config(f)
|
||||
write_PWM_config(f)
|
||||
|
||||
write_peripheral_enable(f)
|
||||
write_prototype_file()
|
||||
|
@ -9,6 +9,17 @@ APJ_BOARD_ID 9
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 24000000
|
||||
|
||||
STM32_HSE_ENABLED FALSE
|
||||
STM32_PLLM_VALUE 16
|
||||
STM32_PLLN_VALUE 384
|
||||
STM32_PLLP_VALUE 4
|
||||
STM32_PLLQ_VALUE 8
|
||||
STM32_PLLSRC STM32_PLLSRC_HSI
|
||||
STM32_PREE1 STM32_PREE1_DIV2
|
||||
STM32_PREE2 STM32_PREE2_DIV1
|
||||
|
||||
STM32_PWM_USE_TIM3 TRUE
|
||||
|
||||
# board voltage
|
||||
STM32_VDD 330U
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user