2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*
|
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include "GPIO.h"
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
|
2018-01-06 06:22:05 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
|
2018-01-13 01:34:48 -04:00
|
|
|
// GPIO pin table from hwdef.dat
|
2018-01-06 06:22:05 -04:00
|
|
|
static struct gpio_entry {
|
|
|
|
uint8_t pin_num;
|
|
|
|
bool enabled;
|
2018-01-13 01:34:48 -04:00
|
|
|
uint8_t pwm_num;
|
2018-01-06 06:22:05 -04:00
|
|
|
ioline_t pal_line;
|
2018-03-16 18:49:40 -03:00
|
|
|
uint16_t port;
|
2018-01-13 01:34:48 -04:00
|
|
|
} _gpio_tab[] = HAL_GPIO_PINS;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-11 21:49:33 -04:00
|
|
|
#define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab)
|
2018-01-06 06:22:05 -04:00
|
|
|
#define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
|
|
|
|
|
|
|
|
/*
|
|
|
|
map a user pin number to a GPIO table entry
|
|
|
|
*/
|
2018-03-25 07:43:42 -03:00
|
|
|
static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
|
2018-01-06 06:22:05 -04:00
|
|
|
{
|
2018-01-11 21:49:33 -04:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
|
2018-01-06 06:22:05 -04:00
|
|
|
if (pin_num == _gpio_tab[i].pin_num) {
|
2018-03-25 07:43:42 -03:00
|
|
|
if (check_enabled && !_gpio_tab[i].enabled) {
|
2018-01-10 17:50:25 -04:00
|
|
|
return NULL;
|
|
|
|
}
|
2018-01-06 06:22:05 -04:00
|
|
|
return &_gpio_tab[i];
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
static void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel);
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
static EXTConfig extcfg;
|
|
|
|
static AP_HAL::Proc ext_irq[EXT_MAX_CHANNELS]; // ext int irq list
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
GPIO::GPIO()
|
2018-01-05 02:19:51 -04:00
|
|
|
{}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void GPIO::init()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-13 01:34:48 -04:00
|
|
|
// auto-disable pins being used for PWM output based on BRD_PWM_COUNT parameter
|
2018-01-06 06:22:05 -04:00
|
|
|
uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
|
2018-01-11 21:49:33 -04:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
|
2018-01-13 01:34:48 -04:00
|
|
|
struct gpio_entry *g = &_gpio_tab[i];
|
|
|
|
if (g->pwm_num != 0) {
|
|
|
|
g->enabled = g->pwm_num > pwm_count;
|
2018-01-06 06:22:05 -04:00
|
|
|
}
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void GPIO::pinMode(uint8_t pin, uint8_t output)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-06 06:22:05 -04:00
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (g) {
|
|
|
|
palSetLineMode(g->pal_line, output);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
int8_t GPIO::analogPinToDigitalPin(uint8_t pin)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint8_t GPIO::read(uint8_t pin)
|
2018-01-06 06:22:05 -04:00
|
|
|
{
|
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (g) {
|
|
|
|
return palReadLine(g->pal_line);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-07 19:40:06 -04:00
|
|
|
return 0;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void GPIO::write(uint8_t pin, uint8_t value)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-06 06:22:05 -04:00
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (g) {
|
|
|
|
if (value == PAL_LOW) {
|
|
|
|
palClearLine(g->pal_line);
|
|
|
|
} else {
|
|
|
|
palSetLine(g->pal_line);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void GPIO::toggle(uint8_t pin)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-06 06:22:05 -04:00
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (g) {
|
|
|
|
palToggleLine(g->pal_line);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Alternative interface: */
|
2018-03-28 06:41:08 -03:00
|
|
|
AP_HAL::DigitalSource* GPIO::channel(uint16_t pin)
|
|
|
|
{
|
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (!g) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return new DigitalSource(g->pal_line);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
/*
|
2018-04-06 20:58:57 -03:00
|
|
|
Attach an interrupt handler to ioline_t
|
2018-03-16 18:49:40 -03:00
|
|
|
*/
|
2018-04-06 20:58:57 -03:00
|
|
|
bool GPIO::_attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
2018-04-06 20:58:57 -03:00
|
|
|
uint8_t pad = PAL_PAD(line);
|
2018-04-08 07:59:45 -03:00
|
|
|
stm32_gpio_t *pal_port = PAL_PORT(line);
|
|
|
|
uint8_t ext_port = 0xff;
|
|
|
|
const struct {
|
|
|
|
stm32_gpio_t *port;
|
|
|
|
uint8_t ext_port;
|
|
|
|
} port_mapping[] = {
|
|
|
|
{ GPIOA, EXT_MODE_GPIOA },
|
|
|
|
{ GPIOB, EXT_MODE_GPIOB },
|
|
|
|
{ GPIOC, EXT_MODE_GPIOC },
|
|
|
|
{ GPIOD, EXT_MODE_GPIOD },
|
|
|
|
{ GPIOE, EXT_MODE_GPIOE },
|
|
|
|
{ GPIOF, EXT_MODE_GPIOF },
|
|
|
|
#ifdef GPIOG
|
|
|
|
{ GPIOG, EXT_MODE_GPIOG },
|
|
|
|
#endif
|
|
|
|
#ifdef GPIOH
|
|
|
|
{ GPIOH, EXT_MODE_GPIOH },
|
|
|
|
#endif
|
|
|
|
#ifdef GPIOI
|
|
|
|
{ GPIOI, EXT_MODE_GPIOI },
|
|
|
|
#endif
|
|
|
|
};
|
2018-04-06 20:58:57 -03:00
|
|
|
// convert the line to a EXT_MODE_GPIOn value, this is STM32 specific
|
2018-04-08 07:59:45 -03:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(port_mapping); i++) {
|
|
|
|
if (pal_port == port_mapping[i].port) {
|
|
|
|
ext_port = port_mapping[i].ext_port;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (ext_port == 0xff) {
|
|
|
|
return false;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
if (p && ext_irq[pad] != nullptr && ext_irq[pad] != p) {
|
|
|
|
// already used
|
|
|
|
return false;
|
|
|
|
} else if (!p && !ext_irq[pad]) {
|
|
|
|
// nothing to remove
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
uint32_t chmode = 0;
|
2018-01-05 02:19:51 -04:00
|
|
|
switch(mode) {
|
|
|
|
case HAL_GPIO_INTERRUPT_LOW:
|
2018-03-16 18:49:40 -03:00
|
|
|
chmode = EXT_CH_MODE_LOW_LEVEL;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_FALLING:
|
2018-03-16 18:49:40 -03:00
|
|
|
chmode = EXT_CH_MODE_FALLING_EDGE;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_RISING:
|
2018-03-16 18:49:40 -03:00
|
|
|
chmode = EXT_CH_MODE_RISING_EDGE;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_BOTH:
|
2018-03-16 18:49:40 -03:00
|
|
|
chmode = EXT_CH_MODE_BOTH_EDGES;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
if (p) {
|
|
|
|
return false;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
if (_ext_started) {
|
|
|
|
extStop(&EXTD1);
|
|
|
|
_ext_started = false;
|
|
|
|
}
|
|
|
|
extcfg.channels[pad].mode = chmode;
|
2018-04-06 20:58:57 -03:00
|
|
|
extcfg.channels[pad].mode |= (p?EXT_CH_MODE_AUTOSTART:0) | ext_port;
|
2018-03-16 18:49:40 -03:00
|
|
|
ext_irq[pad] = p;
|
|
|
|
extcfg.channels[pad].cb = ext_interrupt_cb;
|
2018-01-05 02:19:51 -04:00
|
|
|
extStart(&EXTD1, &extcfg);
|
2018-03-16 18:49:40 -03:00
|
|
|
_ext_started = true;
|
2018-01-05 02:19:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-04-06 20:58:57 -03:00
|
|
|
/*
|
|
|
|
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);
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
bool GPIO::usb_connected(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return _usb_connected;
|
|
|
|
}
|
|
|
|
|
2018-03-28 06:41:08 -03:00
|
|
|
DigitalSource::DigitalSource(ioline_t _line) :
|
|
|
|
line(_line)
|
2018-01-05 02:19:51 -04:00
|
|
|
{}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void DigitalSource::mode(uint8_t output)
|
2018-03-28 06:41:08 -03:00
|
|
|
{
|
|
|
|
palSetLineMode(line, output);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-03-28 06:41:08 -03:00
|
|
|
uint8_t DigitalSource::read()
|
|
|
|
{
|
|
|
|
return palReadLine(line);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-03-28 06:41:08 -03:00
|
|
|
void DigitalSource::write(uint8_t value)
|
|
|
|
{
|
|
|
|
palWriteLine(line, value);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-03-28 06:41:08 -03:00
|
|
|
void DigitalSource::toggle()
|
|
|
|
{
|
|
|
|
palToggleLine(line);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
|
|
|
|
{
|
2018-01-05 02:19:51 -04:00
|
|
|
if (ext_irq[channel] != nullptr) {
|
|
|
|
ext_irq[channel]();
|
|
|
|
}
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif //HAL_BOARD_ChibiOS
|