HAL_ChibiOS: don't require GPIO() markers on PWM outputs

this fixes blheli pass-thru on MindPX-v2
This commit is contained in:
Andrew Tridgell 2018-04-07 09:58:57 +10:00
parent face8151b7
commit 68293c9c11
3 changed files with 26 additions and 37 deletions

View File

@ -125,16 +125,13 @@ AP_HAL::DigitalSource* GPIO::channel(uint16_t pin)
extern const AP_HAL::HAL& hal;
/*
Attach an interrupt handler to a GPIO pin number. The pin number
must be one specified with a GPIO() marker in hwdef.dat
Attach an interrupt handler to ioline_t
*/
bool GPIO::attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode)
bool GPIO::_attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
{
struct gpio_entry *g = gpio_by_pin_num(pin, false);
if (!g) {
return false;
}
uint8_t pad = PAL_PAD(g->pal_line);
uint8_t pad = PAL_PAD(line);
// convert the line to a EXT_MODE_GPIOn value, this is STM32 specific
uint8_t ext_port = uint32_t(PAL_PORT(line)) >> 24;
if (p && ext_irq[pad] != nullptr && ext_irq[pad] != p) {
// already used
return false;
@ -167,7 +164,7 @@ bool GPIO::attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode)
_ext_started = false;
}
extcfg.channels[pad].mode = chmode;
extcfg.channels[pad].mode |= (p?EXT_CH_MODE_AUTOSTART:0) | g->port;
extcfg.channels[pad].mode |= (p?EXT_CH_MODE_AUTOSTART:0) | ext_port;
ext_irq[pad] = p;
extcfg.channels[pad].cb = ext_interrupt_cb;
extStart(&EXTD1, &extcfg);
@ -175,6 +172,19 @@ bool GPIO::attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode)
return true;
}
/*
Attach an interrupt handler to a GPIO pin number. The pin number
must be one specified with a GPIO() marker in hwdef.dat
*/
bool GPIO::attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode)
{
struct gpio_entry *g = gpio_by_pin_num(pin, false);
if (!g) {
return false;
}
return _attach_interrupt(g->pal_line, p, mode);
}
bool GPIO::usb_connected(void)
{
return _usb_connected;
@ -211,16 +221,4 @@ void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
}
}
/*
set the output mode for a pin. Used to restore an alternate function
after using a pin as GPIO. Private to HAL_ChibiOS
*/
void GPIO::_set_mode(uint8_t pin, uint32_t mode)
{
struct gpio_entry *g = gpio_by_pin_num(pin, false);
if (g) {
palSetLineMode(g->pal_line, mode);
}
}
#endif //HAL_BOARD_ChibiOS

View File

@ -48,11 +48,8 @@ public:
void set_usb_connected() { _usb_connected = true; }
/*
set the output mode for a pin. Used to restore an alternate function
after using a pin as GPIO. Private to HAL_ChibiOS
*/
void _set_mode(uint8_t pin, uint32_t mode);
/* attach interrupt via ioline_t */
bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode);
private:
bool _usb_connected;

View File

@ -1171,24 +1171,18 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
return 0;
}
pwm_group &group = *serial_group;
uint8_t chan = group.chan[group.serial.chan];
const ioline_t line = group.pal_lines[group.serial.chan];
uint32_t gpio_mode = PAL_MODE_INPUT_PULLUP;
uint32_t restore_mode = PAL_MODE_ALTERNATE(group.alt_functions[group.serial.chan]) | PAL_STM32_OSPEED_MID2 | PAL_STM32_OTYPE_PUSHPULL;
uint16_t i = 0;
#ifndef HAL_GPIO_LINE_GPIO50
// GPIO lines not setup for PWM outputs in hwdef.dat
return false;
#endif
#if RCOU_SERIAL_TIMING_DEBUG
hal.gpio->pinMode(54, 1);
hal.gpio->pinMode(55, 1);
#endif
// assume GPIO mappings for PWM outputs start at 50
const uint8_t gpio_pin = 50 + chan;
((GPIO *)hal.gpio)->_set_mode(gpio_pin, gpio_mode);
palSetLineMode(line, gpio_mode);
chEvtGetAndClearEvents(serial_event_mask);
@ -1204,7 +1198,7 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
#endif
if (!hal.gpio->attach_interrupt(gpio_pin, serial_bit_irq, HAL_GPIO_INTERRUPT_BOTH)) {
if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, HAL_GPIO_INTERRUPT_BOTH)) {
#if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
#endif
@ -1217,10 +1211,10 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
}
}
hal.gpio->attach_interrupt(gpio_pin, nullptr, 0);
((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0);
irq.waiter = nullptr;
((GPIO *)hal.gpio)->_set_mode(gpio_pin, restore_mode);
palSetLineMode(line, restore_mode);
#if RCOU_SERIAL_TIMING_DEBUG
palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
#endif