HAL_ChibOS: fixed handling of disabled channels

This commit is contained in:
Andrew Tridgell 2018-01-13 13:33:48 +11:00
parent 320ada2002
commit 738d70ef02
2 changed files with 19 additions and 8 deletions

View File

@ -31,14 +31,15 @@ const struct ChibiRCOutput::pwm_group ChibiRCOutput::pwm_group_list[] = { HAL_PW
#define NUM_GROUPS ARRAY_SIZE_SIMPLE(pwm_group_list)
#define CHAN_DISABLED 255
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) {
if (pwm_group_list[i].chan[j] != CHAN_DISABLED) {
total_channels = MAX(total_channels, pwm_group_list[i].chan[j]+1);
}
}
@ -77,7 +78,7 @@ void ChibiRCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
uint16_t grp_ch_mask = 0;
for (uint8_t j=0; j<4; j++) {
if (pwm_group_list[i].chan[j] != 255) {
if (pwm_group_list[i].chan[j] != CHAN_DISABLED) {
grp_ch_mask |= (1U<<pwm_group_list[i].chan[j]);
}
}
@ -201,6 +202,9 @@ void ChibiRCOutput::push_local(void)
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
for (uint8_t j = 0; j < 4; j++) {
uint8_t chan = pwm_group_list[i].chan[j];
if (chan == CHAN_DISABLED) {
continue;
}
if (outmask & (1UL<<chan)) {
uint32_t period_us = period[chan];
if(_output_mode == MODE_PWM_BRUSHED && (fast_channel_mask & (1UL<<chan))) {

View File

@ -516,6 +516,7 @@ def write_PWM_config(f):
group = len(groups)+1
n = int(t[3])
chan_list = [255, 255, 255, 255]
chan_mode = ['PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED', 'PWM_OUTPUT_DISABLED']
for p in pwm_out:
if p.type != t:
continue
@ -531,6 +532,7 @@ def write_PWM_config(f):
errors("Bad PWM number in %s" % p)
pwmchan = int(pwmchan_str)
chan_list[chan-1] = pwmchan-1
chan_mode[chan-1] = 'PWM_OUTPUT_ACTIVE_HIGH'
groups.append('HAL_PWM_GROUP%u' % group)
if n in [1, 8]:
# only the advanced timers do 8MHz clocks
@ -547,11 +549,16 @@ def write_PWM_config(f):
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))
{%s, NULL}, \\
{%s, NULL}, \\
{%s, NULL}, \\
{%s, NULL} \\
}, 0, 0}, &PWMD%u}\n''' % (group,
chan_list[0], chan_list[1], chan_list[2], chan_list[3],
pwm_clock,
period,
chan_mode[0], chan_mode[1], chan_mode[2], chan_mode[3],
n))
f.write('#define HAL_PWM_GROUPS %s\n\n' % ','.join(groups))