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-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
|
|
|
|
*/
|
|
|
|
static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num)
|
|
|
|
{
|
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-01-10 17:50:25 -04:00
|
|
|
if (!_gpio_tab[i].enabled) {
|
|
|
|
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);
|
|
|
|
|
|
|
|
static AP_HAL::Proc ext_irq[22]; // ext int irq list
|
|
|
|
static EXTConfig extcfg = {
|
|
|
|
{
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL},
|
|
|
|
{EXT_CH_MODE_DISABLED, NULL}
|
|
|
|
}
|
|
|
|
};
|
|
|
|
|
|
|
|
static const uint32_t irq_port_list[] = {
|
2018-01-16 18:08:01 -04:00
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 0
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 1
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 2
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 3
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 4
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 5
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 6
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 7
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 8
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 9
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 10
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 11
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 12
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 13
|
|
|
|
HAL_GPIO_INTERRUPT_PORT, //Chan 14
|
|
|
|
HAL_GPIO_INTERRUPT_PORT //Chan 15
|
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
|
|
|
{
|
|
|
|
extStart(&EXTD1, &extcfg);
|
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-01-13 00:02:05 -04:00
|
|
|
AP_HAL::DigitalSource* GPIO::channel(uint16_t n) {
|
|
|
|
return new DigitalSource(0);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/* Interrupt interface: */
|
2018-01-13 00:02:05 -04:00
|
|
|
bool GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode) {
|
2018-01-05 02:19:51 -04:00
|
|
|
extStop(&EXTD1);
|
|
|
|
switch(mode) {
|
|
|
|
case HAL_GPIO_INTERRUPT_LOW:
|
|
|
|
extcfg.channels[interrupt_num].mode = EXT_CH_MODE_LOW_LEVEL;
|
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_FALLING:
|
|
|
|
extcfg.channels[interrupt_num].mode = EXT_CH_MODE_FALLING_EDGE;
|
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_RISING:
|
|
|
|
extcfg.channels[interrupt_num].mode = EXT_CH_MODE_RISING_EDGE;
|
|
|
|
break;
|
|
|
|
case HAL_GPIO_INTERRUPT_BOTH:
|
|
|
|
extcfg.channels[interrupt_num].mode = EXT_CH_MODE_BOTH_EDGES;
|
|
|
|
break;
|
|
|
|
default: return false;
|
|
|
|
}
|
|
|
|
extcfg.channels[interrupt_num].mode |= EXT_CH_MODE_AUTOSTART | irq_port_list[interrupt_num];
|
|
|
|
ext_irq[interrupt_num] = p;
|
|
|
|
extcfg.channels[interrupt_num].cb = ext_interrupt_cb;
|
|
|
|
extStart(&EXTD1, &extcfg);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
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-01-13 00:02:05 -04:00
|
|
|
DigitalSource::DigitalSource(uint8_t v) :
|
2018-01-05 02:19:51 -04:00
|
|
|
_v(v)
|
|
|
|
{}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void DigitalSource::mode(uint8_t output)
|
2018-01-05 02:19:51 -04:00
|
|
|
{}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint8_t DigitalSource::read() {
|
2018-01-05 02:19:51 -04:00
|
|
|
return _v;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void DigitalSource::write(uint8_t value) {
|
2018-01-05 02:19:51 -04:00
|
|
|
_v = value;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void DigitalSource::toggle() {
|
2018-01-05 02:19:51 -04:00
|
|
|
_v = !_v;
|
|
|
|
}
|
|
|
|
|
|
|
|
void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel) {
|
|
|
|
if (ext_irq[channel] != nullptr) {
|
|
|
|
ext_irq[channel]();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif //HAL_BOARD_ChibiOS
|