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/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include "GPIO.h"
|
|
|
|
|
2018-01-06 06:22:05 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2019-11-15 00:03:33 -04:00
|
|
|
#include "hwdef/common/stm32_util.h"
|
2018-01-06 06:22:05 -04:00
|
|
|
|
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-08-06 01:18:52 -03:00
|
|
|
AP_HAL::GPIO::irq_handler_fn_t fn; // callback for GPIO interface
|
2018-08-29 01:10:09 -03:00
|
|
|
bool is_input;
|
|
|
|
uint8_t mode;
|
2020-04-22 02:57:36 -03:00
|
|
|
thread_reference_t thd_wait;
|
2018-01-13 01:34:48 -04:00
|
|
|
} _gpio_tab[] = HAL_GPIO_PINS;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-08-02 20:27:17 -03:00
|
|
|
#define NUM_PINS ARRAY_SIZE(_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-08-02 20:27:17 -03:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(_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
|
|
|
|
2018-06-02 12:54:38 -03:00
|
|
|
static void pal_interrupt_cb(void *arg);
|
2018-08-06 01:18:52 -03:00
|
|
|
static void pal_interrupt_cb_functor(void *arg);
|
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-08-02 20:27:17 -03:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(_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
|
|
|
}
|
|
|
|
}
|
2019-12-29 04:08:56 -04:00
|
|
|
#ifdef HAL_PIN_ALT_CONFIG
|
|
|
|
setup_alt_config();
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2019-12-29 04:08:56 -04:00
|
|
|
#ifdef HAL_PIN_ALT_CONFIG
|
|
|
|
/*
|
|
|
|
alternative config table, selected using BRD_ALT_CONFIG
|
|
|
|
*/
|
|
|
|
static const struct alt_config {
|
|
|
|
uint8_t alternate;
|
|
|
|
uint16_t mode;
|
|
|
|
ioline_t line;
|
|
|
|
} alternate_config[] HAL_PIN_ALT_CONFIG;
|
|
|
|
|
|
|
|
/*
|
|
|
|
change pin configuration based on ALT() lines in hwdef.dat
|
|
|
|
*/
|
|
|
|
void GPIO::setup_alt_config(void)
|
|
|
|
{
|
|
|
|
AP_BoardConfig *bc = AP::boardConfig();
|
|
|
|
if (!bc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
const uint8_t alt = bc->get_alt_config();
|
|
|
|
if (alt == 0) {
|
|
|
|
// use defaults
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
|
|
|
|
if (alt == alternate_config[i].alternate) {
|
|
|
|
const iomode_t mode = alternate_config[i].mode & ~PAL_STM32_HIGH;
|
|
|
|
const uint8_t odr = (alternate_config[i].mode & PAL_STM32_HIGH)?1:0;
|
|
|
|
palSetLineMode(alternate_config[i].line, mode);
|
|
|
|
palWriteLine(alternate_config[i].line, odr);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif // HAL_PIN_ALT_CONFIG
|
|
|
|
|
|
|
|
|
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) {
|
2018-08-29 01:10:09 -03:00
|
|
|
if (!output && g->is_input &&
|
|
|
|
(g->mode == PAL_MODE_INPUT_PULLUP ||
|
|
|
|
g->mode == PAL_MODE_INPUT_PULLDOWN)) {
|
|
|
|
// already set
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
g->mode = output?PAL_MODE_OUTPUT_PUSHPULL:PAL_MODE_INPUT;
|
2019-11-15 00:03:33 -04:00
|
|
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4)
|
|
|
|
if (g->mode == PAL_MODE_OUTPUT_PUSHPULL) {
|
|
|
|
// retain OPENDRAIN if already set
|
|
|
|
iomode_t old_mode = palReadLineMode(g->pal_line);
|
|
|
|
if ((old_mode & PAL_MODE_OUTPUT_OPENDRAIN) == PAL_MODE_OUTPUT_OPENDRAIN) {
|
|
|
|
g->mode = PAL_MODE_OUTPUT_OPENDRAIN;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
2018-08-29 01:10:09 -03:00
|
|
|
palSetLineMode(g->pal_line, g->mode);
|
|
|
|
g->is_input = !output;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
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) {
|
2018-08-29 01:10:09 -03:00
|
|
|
if (g->is_input) {
|
|
|
|
// control pullup/pulldown
|
|
|
|
g->mode = value==1?PAL_MODE_INPUT_PULLUP:PAL_MODE_INPUT_PULLDOWN;
|
|
|
|
palSetLineMode(g->pal_line, g->mode);
|
|
|
|
} else if (value == PAL_LOW) {
|
2018-01-06 06:22:05 -04:00
|
|
|
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;
|
|
|
|
|
2019-10-20 10:31:12 -03:00
|
|
|
/*
|
2018-08-06 01:18:52 -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,
|
|
|
|
irq_handler_fn_t fn,
|
|
|
|
INTERRUPT_TRIGGER_TYPE mode)
|
|
|
|
{
|
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin, false);
|
|
|
|
if (!g) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!_attach_interrupt(g->pal_line,
|
|
|
|
palcallback_t(fn?pal_interrupt_cb_functor:nullptr),
|
|
|
|
g,
|
|
|
|
mode)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
g->fn = fn;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
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-08-06 01:18:52 -03:00
|
|
|
{
|
|
|
|
return _attach_interrupt(line, palcallback_t(p?pal_interrupt_cb:nullptr), (void*)p, mode);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool GPIO::attach_interrupt(uint8_t pin,
|
|
|
|
AP_HAL::Proc proc,
|
|
|
|
INTERRUPT_TRIGGER_TYPE mode) {
|
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin, false);
|
|
|
|
if (!g) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return _attach_interrupt(g->pal_line, proc, mode);
|
|
|
|
}
|
|
|
|
|
2020-04-22 02:57:36 -03:00
|
|
|
bool GPIO::_attach_interruptI(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
|
|
|
uint32_t chmode = 0;
|
2018-01-05 02:19:51 -04:00
|
|
|
switch(mode) {
|
2018-08-06 01:18:52 -03:00
|
|
|
case INTERRUPT_FALLING:
|
2018-06-02 12:54:38 -03:00
|
|
|
chmode = PAL_EVENT_MODE_FALLING_EDGE;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
2018-08-06 01:18:52 -03:00
|
|
|
case INTERRUPT_RISING:
|
2018-06-02 12:54:38 -03:00
|
|
|
chmode = PAL_EVENT_MODE_RISING_EDGE;
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
2018-08-06 01:18:52 -03:00
|
|
|
case INTERRUPT_BOTH:
|
2018-06-02 12:54:38 -03:00
|
|
|
chmode = PAL_EVENT_MODE_BOTH_EDGES;
|
2018-03-16 18:49:40 -03:00
|
|
|
break;
|
|
|
|
default:
|
|
|
|
if (p) {
|
|
|
|
return false;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
break;
|
2019-10-20 10:31:12 -03:00
|
|
|
}
|
2018-08-06 01:18:52 -03:00
|
|
|
|
|
|
|
palevent_t *pep = pal_lld_get_line_event(line);
|
|
|
|
if (pep->cb && p != nullptr) {
|
|
|
|
// the pad is already being used for a callback
|
|
|
|
return false;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-08-02 20:57:57 -03:00
|
|
|
|
2018-08-06 01:18:52 -03:00
|
|
|
if (!p) {
|
|
|
|
chmode = PAL_EVENT_MODE_DISABLED;
|
2018-04-06 20:58:57 -03:00
|
|
|
}
|
2018-08-06 01:18:52 -03:00
|
|
|
|
|
|
|
palDisableLineEventI(line);
|
|
|
|
palSetLineCallbackI(line, cb, p);
|
|
|
|
palEnableLineEventI(line, chmode);
|
|
|
|
|
|
|
|
return true;
|
2018-04-06 20:58:57 -03:00
|
|
|
}
|
|
|
|
|
2020-04-22 02:57:36 -03:00
|
|
|
bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
|
|
|
|
{
|
|
|
|
osalSysLock();
|
|
|
|
bool ret = _attach_interruptI(line, cb, p, mode);
|
|
|
|
osalSysUnlock();
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
}
|
|
|
|
|
2020-04-22 02:57:36 -03:00
|
|
|
static void pal_interrupt_cb(void *arg)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
2018-06-02 12:54:38 -03:00
|
|
|
if (arg != nullptr) {
|
|
|
|
((AP_HAL::Proc)arg)();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2020-04-22 02:57:36 -03:00
|
|
|
static void pal_interrupt_cb_functor(void *arg)
|
2018-08-06 01:18:52 -03:00
|
|
|
{
|
|
|
|
const uint32_t now = AP_HAL::micros();
|
|
|
|
|
|
|
|
struct gpio_entry *g = (gpio_entry *)arg;
|
|
|
|
if (g == nullptr) {
|
|
|
|
// what?
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (!(g->fn)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
(g->fn)(g->pin_num, palReadLine(g->pal_line), now);
|
|
|
|
}
|
2020-04-22 02:57:36 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
handle interrupt from pin change for wait_pin()
|
|
|
|
*/
|
|
|
|
static void pal_interrupt_wait(void *arg)
|
|
|
|
{
|
|
|
|
osalSysLockFromISR();
|
|
|
|
struct gpio_entry *g = (gpio_entry *)arg;
|
|
|
|
if (g == nullptr || g->thd_wait == nullptr) {
|
|
|
|
osalSysUnlockFromISR();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
osalThreadResumeI(&g->thd_wait, MSG_OK);
|
|
|
|
osalSysUnlockFromISR();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
block waiting for a pin to change. A timeout of 0 means wait
|
|
|
|
forever. Return true on pin change, false on timeout
|
|
|
|
*/
|
|
|
|
bool GPIO::wait_pin(uint8_t pin, INTERRUPT_TRIGGER_TYPE mode, uint32_t timeout_us)
|
|
|
|
{
|
|
|
|
struct gpio_entry *g = gpio_by_pin_num(pin);
|
|
|
|
if (!g) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
osalSysLock();
|
|
|
|
if (g->thd_wait) {
|
|
|
|
// only allow single waiter
|
|
|
|
osalSysUnlock();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!_attach_interruptI(g->pal_line,
|
|
|
|
palcallback_t(pal_interrupt_wait),
|
|
|
|
g,
|
|
|
|
mode)) {
|
|
|
|
osalSysUnlock();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, TIME_US2I(timeout_us));
|
|
|
|
_attach_interruptI(g->pal_line,
|
|
|
|
palcallback_t(nullptr),
|
2020-04-22 02:58:35 -03:00
|
|
|
nullptr,
|
2020-04-22 02:57:36 -03:00
|
|
|
mode);
|
|
|
|
osalSysUnlock();
|
2020-04-22 02:58:35 -03:00
|
|
|
|
|
|
|
return msg == MSG_OK;
|
2020-04-22 02:57:36 -03:00
|
|
|
}
|