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
|
|
|
|
*/
|
2022-02-20 23:44:56 -04:00
|
|
|
|
|
|
|
#include <hal.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
#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"
|
2020-09-21 05:29:40 -03:00
|
|
|
#include <AP_InternalError/AP_InternalError.h>
|
2021-07-14 19:39:37 -03:00
|
|
|
#ifndef HAL_BOOTLOADER_BUILD
|
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
|
|
|
#endif
|
2020-09-21 05:29:40 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
#endif
|
2021-07-14 19:39:37 -03:00
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2022-04-03 20:54:20 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2018-01-06 06:22:05 -04:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
#include <AP_IOMCU/AP_IOMCU.h>
|
|
|
|
extern AP_IOMCU iomcu;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
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
|
2023-03-03 09:29:42 -04:00
|
|
|
thread_reference_t thd_wait;
|
2018-08-29 01:10:09 -03:00
|
|
|
bool is_input;
|
|
|
|
uint8_t mode;
|
2020-09-21 05:29:40 -03:00
|
|
|
uint16_t isr_quota;
|
2023-03-03 09:29:42 -04:00
|
|
|
uint8_t isr_disabled_ticks;
|
|
|
|
AP_HAL::GPIO::INTERRUPT_TRIGGER_TYPE isr_mode;
|
2018-01-13 01:34:48 -04:00
|
|
|
} _gpio_tab[] = HAL_GPIO_PINS;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-06 06:22:05 -04:00
|
|
|
/*
|
|
|
|
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++) {
|
2021-10-10 01:45:39 -03:00
|
|
|
const auto &t = _gpio_tab[i];
|
|
|
|
if (pin_num == t.pin_num) {
|
|
|
|
if (check_enabled && t.pwm_num != 0 && !t.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
|
|
|
{
|
2021-07-14 19:39:37 -03:00
|
|
|
#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) && !defined(HAL_BOOTLOADER_BUILD)
|
|
|
|
uint8_t chan_offset = 0;
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled()) {
|
2021-09-20 10:44:46 -03:00
|
|
|
uint8_t GPIO_mask = 0;
|
|
|
|
for (uint8_t i=0; i<8; i++) {
|
|
|
|
if (SRV_Channels::is_GPIO(i)) {
|
|
|
|
GPIO_mask |= 1U << i;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
iomcu.set_GPIO_mask(GPIO_mask);
|
2021-07-14 19:39:37 -03:00
|
|
|
chan_offset = 8;
|
|
|
|
}
|
|
|
|
#endif
|
2022-04-20 22:24:59 -03:00
|
|
|
// auto-disable pins being used for PWM output
|
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) {
|
2021-07-24 04:07:30 -03:00
|
|
|
g->enabled = SRV_Channels::is_GPIO((g->pwm_num-1)+chan_offset);
|
2018-01-06 06:22:05 -04:00
|
|
|
}
|
|
|
|
}
|
2021-07-14 19:39:37 -03:00
|
|
|
#endif // HAL_BOOTLOADER_BUILD
|
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
|
2020-10-27 22:01:14 -03:00
|
|
|
// chosen alternative config
|
|
|
|
uint8_t GPIO::alt_config;
|
|
|
|
|
2019-12-29 04:08:56 -04:00
|
|
|
/*
|
|
|
|
alternative config table, selected using BRD_ALT_CONFIG
|
|
|
|
*/
|
|
|
|
static const struct alt_config {
|
|
|
|
uint8_t alternate;
|
|
|
|
uint16_t mode;
|
|
|
|
ioline_t line;
|
2020-10-27 22:01:14 -03:00
|
|
|
PERIPH_TYPE periph_type;
|
|
|
|
uint8_t periph_instance;
|
2019-12-29 04:08:56 -04:00
|
|
|
} 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;
|
|
|
|
}
|
2020-10-27 22:01:14 -03:00
|
|
|
alt_config = bc->get_alt_config();
|
|
|
|
if (alt_config == 0) {
|
2019-12-29 04:08:56 -04:00
|
|
|
// use defaults
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
|
2020-10-27 22:01:14 -03:00
|
|
|
const struct alt_config &alt = alternate_config[i];
|
|
|
|
if (alt_config == alt.alternate) {
|
2021-09-23 15:06:03 -03:00
|
|
|
if (alt.periph_type == PERIPH_TYPE::GPIO) {
|
|
|
|
// enable pin in GPIO table
|
|
|
|
for (uint8_t j=0; j<ARRAY_SIZE(_gpio_tab); j++) {
|
|
|
|
struct gpio_entry *g = &_gpio_tab[j];
|
|
|
|
if (g->pal_line == alt.line) {
|
|
|
|
g->enabled = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
continue;
|
|
|
|
}
|
2020-10-27 22:01:14 -03:00
|
|
|
const iomode_t mode = alt.mode & ~PAL_STM32_HIGH;
|
|
|
|
const uint8_t odr = (alt.mode & PAL_STM32_HIGH)?1:0;
|
|
|
|
palSetLineMode(alt.line, mode);
|
|
|
|
palWriteLine(alt.line, odr);
|
2019-12-29 04:08:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif // HAL_PIN_ALT_CONFIG
|
|
|
|
|
2020-10-27 22:01:14 -03:00
|
|
|
/*
|
|
|
|
resolve an ioline_t to take account of alternative
|
|
|
|
configurations. This allows drivers to get the right ioline_t for an
|
|
|
|
alternative config. Note that this may return 0, meaning the pin is
|
|
|
|
not mapped to this peripheral in the active config
|
|
|
|
*/
|
|
|
|
ioline_t GPIO::resolve_alt_config(ioline_t base, PERIPH_TYPE ptype, uint8_t instance)
|
|
|
|
{
|
|
|
|
#ifdef HAL_PIN_ALT_CONFIG
|
|
|
|
if (alt_config == 0) {
|
|
|
|
// unchanged
|
|
|
|
return base;
|
|
|
|
}
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
|
|
|
|
const struct alt_config &alt = alternate_config[i];
|
|
|
|
if (alt_config == alt.alternate) {
|
|
|
|
if (ptype == alt.periph_type && instance == alt.periph_instance) {
|
|
|
|
// we've reconfigured this peripheral with a different line
|
|
|
|
return alt.line;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// now search for pins that have been configured off via BRD_ALT_CONFIG
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(alternate_config); i++) {
|
|
|
|
const struct alt_config &alt = alternate_config[i];
|
|
|
|
if (alt_config == alt.alternate) {
|
|
|
|
if (alt.line == base) {
|
|
|
|
// this line is no longer available in this config
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
return base;
|
|
|
|
}
|
|
|
|
|
2019-12-29 04:08:56 -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) {
|
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;
|
2023-04-12 00:41:35 -03:00
|
|
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
2019-11-15 00:03:33 -04:00
|
|
|
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
|
|
|
{
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) {
|
|
|
|
iomcu.write_GPIO(pin, value);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
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
|
|
|
{
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) {
|
|
|
|
iomcu.toggle_GPIO(pin);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
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)
|
|
|
|
{
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) {
|
|
|
|
return new IOMCU_DigitalSource(pin);
|
|
|
|
}
|
|
|
|
#endif
|
2018-03-28 06:41:08 -03:00
|
|
|
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;
|
|
|
|
}
|
2023-03-03 09:29:42 -04:00
|
|
|
g->isr_disabled_ticks = 0;
|
|
|
|
g->isr_quota = 0;
|
2018-08-06 01:18:52 -03:00
|
|
|
if (!_attach_interrupt(g->pal_line,
|
|
|
|
palcallback_t(fn?pal_interrupt_cb_functor:nullptr),
|
|
|
|
g,
|
|
|
|
mode)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
g->fn = fn;
|
2023-03-03 09:29:42 -04:00
|
|
|
g->isr_mode = mode;
|
2018-08-06 01:18:52 -03:00
|
|
|
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;
|
|
|
|
}
|
2023-03-03 09:29:42 -04:00
|
|
|
g->isr_disabled_ticks = 0;
|
|
|
|
g->isr_quota = 0;
|
|
|
|
g->isr_mode = mode;
|
2018-08-06 01:18:52 -03:00
|
|
|
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
|
|
|
}
|
|
|
|
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
IOMCU_DigitalSource::IOMCU_DigitalSource(uint8_t _pin) :
|
|
|
|
pin(_pin)
|
|
|
|
{}
|
|
|
|
|
|
|
|
void IOMCU_DigitalSource::write(uint8_t value)
|
|
|
|
{
|
|
|
|
iomcu.write_GPIO(pin, value);
|
|
|
|
}
|
|
|
|
|
|
|
|
void IOMCU_DigitalSource::toggle()
|
|
|
|
{
|
|
|
|
iomcu.toggle_GPIO(pin);
|
|
|
|
}
|
|
|
|
#endif // HAL_WITH_IO_MCU
|
|
|
|
|
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;
|
|
|
|
}
|
2020-09-21 05:29:40 -03:00
|
|
|
if (g->isr_quota >= 1) {
|
|
|
|
/*
|
|
|
|
we have an interrupt quota enabled for this pin. If the
|
|
|
|
quota remaining drops to 1 without it being refreshed in
|
|
|
|
timer_tick then we disable the interrupt source. This is to
|
|
|
|
prevent CPU overload due to very high GPIO interrupt counts
|
|
|
|
*/
|
|
|
|
if (g->isr_quota == 1) {
|
|
|
|
osalSysLockFromISR();
|
|
|
|
palDisableLineEventI(g->pal_line);
|
|
|
|
osalSysUnlockFromISR();
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
g->isr_quota--;
|
|
|
|
}
|
2018-08-06 01:18:52 -03:00
|
|
|
(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();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2022-04-03 20:54:20 -03:00
|
|
|
block waiting for a pin to change. Return true on pin change, false on timeout
|
2020-04-22 02:57:36 -03:00
|
|
|
*/
|
|
|
|
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;
|
|
|
|
}
|
2022-04-03 20:54:20 -03:00
|
|
|
|
|
|
|
// don't allow for very long timeouts, or below the delta
|
|
|
|
timeout_us = constrain_uint32(TIME_US2I(timeout_us), CH_CFG_ST_TIMEDELTA, TIME_US2I(30000U));
|
|
|
|
|
|
|
|
msg_t msg = osalThreadSuspendTimeoutS(&g->thd_wait, timeout_us);
|
2020-04-22 02:57:36 -03:00
|
|
|
_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
|
|
|
}
|
2020-09-21 05:29:40 -03:00
|
|
|
|
2021-07-20 01:19:40 -03:00
|
|
|
// check if a pin number is valid
|
|
|
|
bool GPIO::valid_pin(uint8_t pin) const
|
|
|
|
{
|
2021-09-20 10:44:46 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled() && iomcu.valid_GPIO_pin(pin)) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
#endif
|
2021-07-20 01:19:40 -03:00
|
|
|
return gpio_by_pin_num(pin) != nullptr;
|
|
|
|
}
|
|
|
|
|
2022-04-19 01:24:01 -03:00
|
|
|
// return servo channel associated with GPIO pin. Returns true on success and fills in servo_ch argument
|
|
|
|
// servo_ch uses zero-based indexing
|
|
|
|
bool GPIO::pin_to_servo_channel(uint8_t pin, uint8_t& servo_ch) const
|
|
|
|
{
|
|
|
|
uint8_t fmu_chan_offset = 0;
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled()) {
|
|
|
|
// check if this is one of the main pins
|
|
|
|
uint8_t main_servo_ch = pin;
|
|
|
|
if (iomcu.convert_pin_number(main_servo_ch)) {
|
|
|
|
servo_ch = main_servo_ch;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
// with IOMCU the local (FMU) channels start at 8
|
|
|
|
fmu_chan_offset = 8;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// search _gpio_tab for matching pin
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
|
|
|
|
if (_gpio_tab[i].pin_num == pin) {
|
|
|
|
if (_gpio_tab[i].pwm_num == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
servo_ch = _gpio_tab[i].pwm_num-1+fmu_chan_offset;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-04-12 00:41:35 -03:00
|
|
|
#if defined(STM32F7) || defined(STM32H7) || defined(STM32F4) || defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
2021-10-10 01:45:39 -03:00
|
|
|
|
|
|
|
// allow for save and restore of pin settings
|
|
|
|
bool GPIO::get_mode(uint8_t pin, uint32_t &mode)
|
|
|
|
{
|
|
|
|
auto *p = gpio_by_pin_num(pin);
|
|
|
|
if (!p) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
mode = uint32_t(palReadLineMode(p->pal_line));
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void GPIO::set_mode(uint8_t pin, uint32_t mode)
|
|
|
|
{
|
|
|
|
auto *p = gpio_by_pin_num(pin);
|
|
|
|
if (p) {
|
|
|
|
palSetLineMode(p->pal_line, ioline_t(mode));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2020-09-21 05:29:40 -03:00
|
|
|
#ifndef IOMCU_FW
|
|
|
|
/*
|
|
|
|
timer to setup interrupt quotas for a 100ms period from
|
|
|
|
monitor thread
|
|
|
|
*/
|
|
|
|
void GPIO::timer_tick()
|
|
|
|
{
|
|
|
|
// allow 100k interrupts/second max for GPIO interrupt sources, which is
|
|
|
|
// 10k per 100ms call to timer_tick()
|
|
|
|
const uint16_t quota = 10000U;
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
|
2023-03-03 09:29:42 -04:00
|
|
|
if (_gpio_tab[i].isr_quota != 1) {
|
|
|
|
// Reset quota for next tick
|
|
|
|
_gpio_tab[i].isr_quota = quota;
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
// we ran out of ISR quota for this pin since the last
|
|
|
|
// check. This is not really an internal error, but we use
|
|
|
|
// INTERNAL_ERROR() to get the reporting mechanism
|
|
|
|
|
|
|
|
if (_gpio_tab[i].isr_disabled_ticks == 0) {
|
2020-09-21 05:29:40 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"ISR flood on pin %u", _gpio_tab[i].pin_num);
|
|
|
|
#endif
|
2023-03-03 09:29:42 -04:00
|
|
|
// Only trigger internal error if armed
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
INTERNAL_ERROR(AP_InternalError::error_t::gpio_isr);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (hal.util->get_soft_armed()) {
|
|
|
|
// Don't start counting until disarmed
|
|
|
|
_gpio_tab[i].isr_disabled_ticks = 1;
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
// Increment disabled ticks, don't wrap
|
|
|
|
if (_gpio_tab[i].isr_disabled_ticks < UINT8_MAX) {
|
|
|
|
_gpio_tab[i].isr_disabled_ticks++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// 100 * 100ms = 10 seconds
|
|
|
|
const uint8_t ISR_retry_ticks = 100U;
|
|
|
|
if ((_gpio_tab[i].isr_disabled_ticks > ISR_retry_ticks) && (_gpio_tab[i].fn != nullptr)) {
|
|
|
|
// Try re-enabling
|
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Retrying pin %d after ISR flood", _gpio_tab[i].pin_num);
|
|
|
|
#endif
|
|
|
|
if (attach_interrupt(_gpio_tab[i].pin_num, _gpio_tab[i].fn, _gpio_tab[i].isr_mode)) {
|
|
|
|
// Success, reset quota
|
|
|
|
_gpio_tab[i].isr_quota = quota;
|
|
|
|
} else {
|
|
|
|
// Failed, reset disabled count to try again later
|
|
|
|
_gpio_tab[i].isr_disabled_ticks = 1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// Check for ISR floods
|
|
|
|
bool GPIO::arming_checks(size_t buflen, char *buffer) const
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
|
|
|
|
if (_gpio_tab[i].isr_disabled_ticks != 0) {
|
|
|
|
hal.util->snprintf(buffer, buflen, "Pin %u disabled (ISR flood)", _gpio_tab[i].pin_num);
|
|
|
|
return false;
|
2020-09-21 05:29:40 -03:00
|
|
|
}
|
|
|
|
}
|
2023-03-03 09:29:42 -04:00
|
|
|
return true;
|
2020-09-21 05:29:40 -03:00
|
|
|
}
|
|
|
|
#endif // IOMCU_FW
|