HAL_ChibOS: auto-generate full PWM config

use PWM markers in hwdef.dat to mark each PWM channel
This commit is contained in:
Andrew Tridgell 2018-01-12 19:29:16 +11:00
parent b741c6c29e
commit c639708e22
9 changed files with 180 additions and 79 deletions

View File

@ -27,36 +27,7 @@ extern const AP_HAL::HAL& hal;
extern AP_IOMCU iomcu;
#endif
#define PWM_CLK_FREQ 8000000
#define PWM_US_WIDTH_FROM_CLK(x) ((PWM_CLK_FREQ/1000000)*x)
const struct ChibiRCOutput::pwm_group ChibiRCOutput::pwm_group_list[] =
{
//Group 1 Config
{ //Channels in the Group and respective mapping
{0, 1, 2, 3},
//Group Initial Config
{
8000000, /* 8MHz PWM clock frequency. */
160000, /* Initial PWM period 20ms. */
NULL,
{
//Channel Config
{PWM_OUTPUT_ACTIVE_HIGH, NULL},
{PWM_OUTPUT_ACTIVE_HIGH, NULL},
{PWM_OUTPUT_ACTIVE_HIGH, NULL},
{PWM_OUTPUT_ACTIVE_HIGH, NULL}
},
0,
0
},
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
&PWMD1
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
&PWMD3
#endif
}
};
const struct ChibiRCOutput::pwm_group ChibiRCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
#define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list)
@ -65,12 +36,19 @@ void ChibiRCOutput::init()
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
//Start Pwm groups
pwmStart(pwm_group_list[i].pwm_drv, &pwm_group_list[i].pwm_cfg);
pwmChangePeriod(pwm_group_list[i].pwm_drv, pwm_group_list[i].pwm_cfg.frequency/50);
for (uint8_t j = 0; j < 4; j++ ) {
if (pwm_group_list[i].chan[j] != 255) {
total_channels = MAX(total_channels, pwm_group_list[i].chan[j]+1);
}
}
}
#if HAL_WITH_IO_MCU
if (AP_BoardConfig::io_enabled()) {
iomcu.init();
// with IOMCU the local channels start at 8
chan_offset = 8;
total_channels += chan_offset;
}
#endif
}
@ -79,7 +57,6 @@ void ChibiRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
{
//check if the request spans accross any of the channel groups
uint8_t update_mask = 0;
uint32_t grp_ch_mask;
// greater than 400 doesn't give enough room at higher periods for
// the down pulse
if (freq_hz > 400 && _output_mode != MODE_PWM_BRUSHED) {
@ -98,11 +75,16 @@ void ChibiRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
}
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
grp_ch_mask = 0XF;
uint16_t grp_ch_mask = 0;
for (uint8_t j=0; j<4; j++) {
if (pwm_group_list[i].chan[j] != 255) {
grp_ch_mask |= (1U<<pwm_group_list[i].chan[j]);
}
}
if ((grp_ch_mask & chmask) == grp_ch_mask) {
update_mask |= grp_ch_mask;
pwmChangePeriod(pwm_group_list[i].pwm_drv,
pwm_group_list[i].pwm_cfg.frequency/freq_hz);
pwm_group_list[i].pwm_cfg.frequency/freq_hz);
}
}
if (chmask != update_mask) {
@ -112,6 +94,9 @@ void ChibiRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
uint16_t ChibiRCOutput::get_freq(uint8_t chan)
{
if (chan >= total_channels) {
return 0;
}
#if HAL_WITH_IO_MCU
if (chan < chan_offset) {
return iomcu.get_freq(chan);
@ -132,6 +117,9 @@ uint16_t ChibiRCOutput::get_freq(uint8_t chan)
void ChibiRCOutput::enable_ch(uint8_t chan)
{
if (chan >= total_channels) {
return;
}
if (chan < chan_offset) {
return;
}
@ -148,6 +136,9 @@ void ChibiRCOutput::enable_ch(uint8_t chan)
void ChibiRCOutput::disable_ch(uint8_t chan)
{
if (chan >= total_channels) {
return;
}
if (chan < chan_offset) {
return;
}
@ -165,6 +156,9 @@ void ChibiRCOutput::disable_ch(uint8_t chan)
void ChibiRCOutput::write(uint8_t chan, uint16_t period_us)
{
if (chan >= total_channels) {
return;
}
last_sent[chan] = period_us;
#if HAL_WITH_IO_MCU
@ -212,7 +206,8 @@ void ChibiRCOutput::push_local(void)
}
pwmEnableChannel(pwm_group_list[i].pwm_drv, j, period_us);
} else {
pwmEnableChannel(pwm_group_list[i].pwm_drv, j, PWM_US_WIDTH_FROM_CLK(period_us));
uint32_t width = (pwm_group_list[i].pwm_cfg.frequency/1000000) * period_us;
pwmEnableChannel(pwm_group_list[i].pwm_drv, j, width);
}
}
}
@ -221,6 +216,9 @@ void ChibiRCOutput::push_local(void)
uint16_t ChibiRCOutput::read(uint8_t chan)
{
if (chan >= total_channels) {
return 0;
}
#if HAL_WITH_IO_MCU
if (chan < chan_offset) {
return iomcu.read_channel(chan);
@ -232,6 +230,9 @@ uint16_t ChibiRCOutput::read(uint8_t chan)
void ChibiRCOutput::read(uint16_t* period_us, uint8_t len)
{
if (len > total_channels) {
len = total_channels;
}
#if HAL_WITH_IO_MCU
for (uint8_t i=0; i<MIN(len, chan_offset); i++) {
period_us[i] = iomcu.read_channel(i);
@ -248,11 +249,17 @@ void ChibiRCOutput::read(uint16_t* period_us, uint8_t len)
uint16_t ChibiRCOutput::read_last_sent(uint8_t chan)
{
if (chan >= total_channels) {
return 0;
}
return last_sent[chan];
}
void ChibiRCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
{
if (len > total_channels) {
len = total_channels;
}
for (uint8_t i=0; i<len; i++) {
period_us[i] = read_last_sent(i);
}

View File

@ -55,7 +55,7 @@ public:
private:
struct pwm_group {
uint8_t chan[4]; // chan number, zero based
uint8_t chan[4]; // chan number, zero based, 255 for disabled
PWMConfig pwm_cfg;
PWMDriver* pwm_drv;
};
@ -68,6 +68,9 @@ private:
// offset of first local channel
uint8_t chan_offset;
// total number of channels
uint8_t total_channels;
// last sent values are for all channels
uint16_t last_sent[16];

View File

@ -22,10 +22,6 @@
#define PPM_ICU_CHANNEL ICU_CHANNEL_2
#endif
#ifndef HRT_TIMER
#define HRT_TIMER GPTD5
#endif
#ifndef HAL_BOARD_INIT_HOOK_DEFINE
#define HAL_BOARD_INIT_HOOK_DEFINE
#endif

View File

@ -166,18 +166,48 @@
/*
* GPT driver system settings.
*/
#ifndef STM32_GPT_USE_TIM1
#define STM32_GPT_USE_TIM1 FALSE
#endif
#ifndef STM32_GPT_USE_TIM2
#define STM32_GPT_USE_TIM2 FALSE
#endif
#ifndef STM32_GPT_USE_TIM3
#define STM32_GPT_USE_TIM3 FALSE
#endif
#ifndef STM32_GPT_USE_TIM4
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM5 TRUE
#endif
#ifndef STM32_GPT_USE_TIM5
#define STM32_GPT_USE_TIM5 FALSE
#endif
#ifndef STM32_GPT_USE_TIM6
#define STM32_GPT_USE_TIM6 FALSE
#endif
#ifndef STM32_GPT_USE_TIM7
#define STM32_GPT_USE_TIM7 FALSE
#endif
#ifndef STM32_GPT_USE_TIM8
#define STM32_GPT_USE_TIM8 FALSE
#endif
#ifndef STM32_GPT_USE_TIM9
#define STM32_GPT_USE_TIM9 FALSE
#endif
#ifndef STM32_GPT_USE_TIM10
#define STM32_GPT_USE_TIM10 FALSE
#endif
#ifndef STM32_GPT_USE_TIM11
#define STM32_GPT_USE_TIM11 FALSE
#endif
#ifndef STM32_GPT_USE_TIM12
#define STM32_GPT_USE_TIM12 FALSE
#endif
#ifndef STM32_GPT_USE_TIM13
#define STM32_GPT_USE_TIM13 FALSE
#endif
#ifndef STM32_GPT_USE_TIM14
#define STM32_GPT_USE_TIM14 FALSE
#endif
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
@ -285,7 +315,9 @@
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#ifndef STM32_ST_USE_TIMER
#define STM32_ST_USE_TIMER 2
#endif
/*
* UART driver system settings.

View File

@ -195,7 +195,7 @@ int _isatty(struct _reent *r, int fd)
}
__attribute__((used))
pid_t _getpid()
pid_t _getpid(void)
{
return 0;
}

View File

@ -99,8 +99,8 @@ PD9 USART3_RX USART3
PD10 FRAM_CS CS
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
PD13 TIM4_CH2 TIM4
PD14 TIM4_CH3 TIM4
PD13 TIM4_CH2 TIM4 PWM5
PD14 TIM4_CH3 TIM4 PWM6
PD15 MPU_DRDY INPUT
# UART8 serial4 GPS2
@ -114,12 +114,12 @@ PE6 SPI4_MOSI SPI4
# UART7 debug console
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1
PE9 TIM1_CH1 TIM1 PWM4
PE10 VDD_5V_HIPOWER_OC INPUT
PE11 TIM1_CH2 TIM1
PE11 TIM1_CH2 TIM1 PWM3
PE12 FMU_LED_AMBER OUTPUT
PE13 TIM1_CH3 TIM1
PE14 TIM1_CH4 TIM1
PE13 TIM1_CH3 TIM1 PWM2
PE14 TIM1_CH4 TIM1 PWM1
PE15 VDD_5V_PERIPH_OC INPUT
# SPI device table. The DEVID values are chosen to match the PX4 port

View File

@ -111,8 +111,8 @@ PD10 FRAM_CS CS
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
PD13 TIM4_CH2 TIM4 # FMU_CH5
PD14 TIM4_CH3 TIM4 # FMU_CH6
PD13 TIM4_CH2 TIM4 PWM5
PD14 TIM4_CH3 TIM4 PWM6
PD15 MPU9250_DRDY INPUT
@ -128,12 +128,12 @@ PE6 8266_RST OUTPUT LOW
# UART7 is debug
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1 # FMU_CH4
PE9 TIM1_CH1 TIM1 PWM4
PE10 8266_CTS OUTPUT HIGH
PE11 TIM1_CH2 TIM1 # FMU_CH3
PE11 TIM1_CH2 TIM1 PWM3
PE12 MAG_DRDY INPUT
PE13 TIM1_CH3 TIM1 # FMU_CH2
PE14 TIM1_CH4 TIM1 # FMU_CH1
PE13 TIM1_CH3 TIM1 PWM2
PE14 TIM1_CH4 TIM1 PWM1
PE15 MAG_CS CS
# SPI device table. The DEVID values are chosen to match the PX4 port

View File

@ -1,3 +1,4 @@
# hw definition file for processing by chibios_hwdef.py
# for MindPX-v2 hardware
@ -11,6 +12,9 @@ APJ_BOARD_ID 88
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
STM32_ST_USE_TIMER 5
HRT_TIMER 6
# board voltage
STM32_VDD 330U
@ -34,8 +38,8 @@ UART_ORDER OTG1 UART4 USART2 USART3 UART8 USART1
# UART4 is GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA2 TIM2_CH3 TIM2 # PWM_OUT7
PA3 TIM2_CH4 TIM2 # PWM_OUT8
PA2 TIM2_CH3 TIM2 PWM15
PA3 TIM2_CH4 TIM2 PWM16
PA4 VDD_5V_SENS ADC1
# SPI1 is fram bus
@ -53,13 +57,13 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA15 TIM2_CH1 TIM2 # PWM_OUT5
PA15 TIM2_CH1 TIM2 PWM13
PB0 TIM3_CH3 TIM3 # PWM_OUT3
PB1 TIM3_CH4 TIM3 # PWM_OUT4
PB0 TIM3_CH3 TIM3 PWM11
PB1 TIM3_CH4 TIM3 PWM12
PB2 GYRO_CS CS
PB3 TIM2_CH2 TIM2 # PWM_OUT6
PB4 TIM3_CH1 TIM3 # PWM_OUT1
PB3 TIM2_CH2 TIM2 PWM14
PB4 TIM3_CH1 TIM3 PWM9
PB5 SPI1_MOSI SPI1
# USART1 is SBUS
@ -87,8 +91,8 @@ PC2 BAT_VOLT_SENS ADC1
PC3 FMU_ADC1 ADC1
PC4 FMU_ADC2 ADC1
PC5 FMU_ADC3 ADC1
PC6 FMU_GPIO2 INPUT # RCIN
PC7 TIM3_CH2 TIM3 # PWM_OUT2
PC6 TIM8_CH1 TIM8 PPMIN # RC PPM input
PC7 TIM3_CH2 TIM3 PWM10
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
@ -117,10 +121,10 @@ PD9 USART3_RX USART3
PD10 NRF_INT INPUT
PD11 ACCEL_MAG_CS CS
PD12 TIM4_CH1 TIM4 # FMU_CH5
PD13 TIM4_CH2 TIM4 # FMU_CH6
PD14 TIM4_CH3 TIM4 # FMU_CH7
PD15 TIM4_CH4 TIM4 # FMU_CH8
PD12 TIM4_CH1 TIM4 PWM5
PD13 TIM4_CH2 TIM4 PWM6
PD14 TIM4_CH3 TIM4 PWM7
PD15 TIM4_CH4 TIM4 PWM8
# UART8 is FrSky
PE0 UART8_RX UART8
@ -137,12 +141,12 @@ PE6 SPI4_MOSI SPI4
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1 # FMU_CH1
PE9 TIM1_CH1 TIM1 PWM1
PE10 MPU_DRDY INPUT
PE11 TIM1_CH2 TIM1 # FMU_CH2
PE11 TIM1_CH2 TIM1 PWM2
PE12 FRAM_CS CS
PE13 TIM1_CH3 TIM1 # FMU_CH3
PE14 TIM1_CH4 TIM1 # FMU_CH4
PE13 TIM1_CH3 TIM1 PWM3
PE14 TIM1_CH4 TIM1 PWM4
PE15 NRF_CS CS
# SPI device table

View File

@ -104,7 +104,15 @@ class generic_pin(object):
self.af = None
def has_extra(self, v):
return v in self.extra
'''return true if we have the given extra token'''
return v in self.extra
def extra_prefix(self, prefix):
'''find an extra token starting with the given prefix'''
for e in self.extra:
if e.startswith(prefix):
return e
return None
def is_RTS(self):
'''return true if this is a RTS pin'''
@ -197,13 +205,14 @@ class generic_pin(object):
return self.get_AFIO()
def __str__(self):
afstr = ''
adcstr = ''
str = ''
if self.af is not None:
afstr = " AF%u" % self.af
str += " AF%u" % self.af
if self.type.startswith('ADC1'):
adcstr = " ADC1_IN%u" % get_ADC1_chan(mcu_type, self.portpin)
return "P%s%u %s %s%s%s" % (self.port, self.pin, self.label, self.type, afstr, adcstr)
str += " ADC1_IN%u" % get_ADC1_chan(mcu_type, self.portpin)
if self.extra_prefix('PWM'):
str += " %s" % self.extra_prefix('PWM')
return "P%s%u %s %s%s" % (self.port, self.pin, self.label, self.type, str)
# setup default as input pins
for port in ports:
@ -286,7 +295,12 @@ def write_mcu_config(f):
f.write('#define %s\n' % d)
if d.startswith('define '):
f.write('#define %s\n' % d[7:])
hrt_timer = get_config('HRT_TIMER', default='5')
hrt_timer = int(hrt_timer)
f.write('#define HRT_TIMER GPTD%u\n' % hrt_timer)
f.write('#define STM32_GPT_USE_TIM%u TRUE\n' % hrt_timer)
f.write('\n')
def write_USB_config(f):
'''write USB config defines'''
@ -433,7 +447,8 @@ def write_PWM_config(f):
if p.has_extra('PPMIN'):
ppm_in = p
else:
pwm_out.append(p)
if p.extra_prefix('PWM') is not None:
pwm_out.append(p)
if p.type not in pwm_timers:
pwm_timers.append(p.type)
if ppm_in is not None:
@ -445,11 +460,55 @@ def write_PWM_config(f):
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')
f.write('// PWM timer 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')
f.write('#define STM32_TIM%u_SUPPRESS_ISR\n' % n)
f.write('\n')
f.write('// PWM output config\n')
groups = []
for t in sorted(pwm_timers):
group = len(groups)+1
n = int(t[3])
chan_list = [255, 255, 255, 255]
for p in pwm_out:
if p.type != t:
continue
chan_str = p.label[7]
if not is_int(chan_str):
error("Bad channel for PWM %s" % p)
chan = int(chan_str)
if chan not in [1,2,3,4]:
error("Bad channel number %u for PWM %s" % (chan, p))
pwm = p.extra_prefix('PWM')
pwmchan_str = pwm[3:]
if not is_int(pwmchan_str):
errors("Bad PWM number in %s" % p)
pwmchan = int(pwmchan_str)
chan_list[chan-1] = pwmchan-1
groups.append('HAL_PWM_GROUP%u' % group)
if n in [1, 8]:
# only the advanced timers do 8MHz clocks
pwm_clock = 8000000
else:
pwm_clock = 1000000
period = 20000 * pwm_clock / 1000000
f.write('''#define HAL_PWM_GROUP%u { \\
{%u, %u, %u, %u}, \\
/* Group Initial Config */ \\
{ \\
%u, /* PWM clock frequency. */ \\
%u, /* Initial PWM period 20ms. */ \\
NULL, /* no callback */ \\
{ \\
/* Channel Config */ \\
{PWM_OUTPUT_ACTIVE_HIGH, NULL}, \\
{PWM_OUTPUT_ACTIVE_HIGH, NULL}, \\
{PWM_OUTPUT_ACTIVE_HIGH, NULL}, \\
{PWM_OUTPUT_ACTIVE_HIGH, NULL} \\
}, 0, 0}, &PWMD%u}\n''' % (group, chan_list[0], chan_list[1], chan_list[2], chan_list[3], pwm_clock, period, n))
f.write('#define HAL_PWM_GROUPS %s\n\n' % ','.join(groups))