123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263 |
- #include "GPIO.h"
- #include <AP_BoardConfig/AP_BoardConfig.h>
- using namespace ChibiOS;
- static struct gpio_entry {
- uint8_t pin_num;
- bool enabled;
- uint8_t pwm_num;
- ioline_t pal_line;
- AP_HAL::GPIO::irq_handler_fn_t fn;
- bool is_input;
- uint8_t mode;
- } _gpio_tab[] = HAL_GPIO_PINS;
- #define NUM_PINS ARRAY_SIZE(_gpio_tab)
- #define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
- static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
- {
- for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
- if (pin_num == _gpio_tab[i].pin_num) {
- if (check_enabled && !_gpio_tab[i].enabled) {
- return NULL;
- }
- return &_gpio_tab[i];
- }
- }
- return NULL;
- }
- static void pal_interrupt_cb(void *arg);
- static void pal_interrupt_cb_functor(void *arg);
- GPIO::GPIO()
- {}
- void GPIO::init()
- {
-
- uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
- for (uint8_t i=0; i<ARRAY_SIZE(_gpio_tab); i++) {
- struct gpio_entry *g = &_gpio_tab[i];
- if (g->pwm_num != 0) {
- g->enabled = g->pwm_num > pwm_count;
- }
- }
- }
- void GPIO::pinMode(uint8_t pin, uint8_t output)
- {
- struct gpio_entry *g = gpio_by_pin_num(pin);
- if (g) {
- if (!output && g->is_input &&
- (g->mode == PAL_MODE_INPUT_PULLUP ||
- g->mode == PAL_MODE_INPUT_PULLDOWN)) {
-
- return;
- }
- g->mode = output?PAL_MODE_OUTPUT_PUSHPULL:PAL_MODE_INPUT;
- palSetLineMode(g->pal_line, g->mode);
- g->is_input = !output;
- }
- }
- uint8_t GPIO::read(uint8_t pin)
- {
- struct gpio_entry *g = gpio_by_pin_num(pin);
- if (g) {
- return palReadLine(g->pal_line);
- }
- return 0;
- }
- void GPIO::write(uint8_t pin, uint8_t value)
- {
- struct gpio_entry *g = gpio_by_pin_num(pin);
- if (g) {
- if (g->is_input) {
-
- g->mode = value==1?PAL_MODE_INPUT_PULLUP:PAL_MODE_INPUT_PULLDOWN;
- palSetLineMode(g->pal_line, g->mode);
- } else if (value == PAL_LOW) {
- palClearLine(g->pal_line);
- } else {
- palSetLine(g->pal_line);
- }
- }
- }
- void GPIO::toggle(uint8_t pin)
- {
- struct gpio_entry *g = gpio_by_pin_num(pin);
- if (g) {
- palToggleLine(g->pal_line);
- }
- }
- 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);
- }
- extern const AP_HAL::HAL& hal;
- 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;
- }
- bool GPIO::_attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
- {
- 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);
- }
- bool GPIO::_attach_interrupt(ioline_t line, palcallback_t cb, void *p, uint8_t mode)
- {
- uint32_t chmode = 0;
- switch(mode) {
- case INTERRUPT_FALLING:
- chmode = PAL_EVENT_MODE_FALLING_EDGE;
- break;
- case INTERRUPT_RISING:
- chmode = PAL_EVENT_MODE_RISING_EDGE;
- break;
- case INTERRUPT_BOTH:
- chmode = PAL_EVENT_MODE_BOTH_EDGES;
- break;
- default:
- if (p) {
- return false;
- }
- break;
- }
- osalSysLock();
- palevent_t *pep = pal_lld_get_line_event(line);
- if (pep->cb && p != nullptr) {
-
- osalSysUnlock();
- return false;
- }
- if (!p) {
- chmode = PAL_EVENT_MODE_DISABLED;
- }
- palDisableLineEventI(line);
- palSetLineCallbackI(line, cb, p);
- palEnableLineEventI(line, chmode);
- osalSysUnlock();
- return true;
- }
- bool GPIO::usb_connected(void)
- {
- return _usb_connected;
- }
- DigitalSource::DigitalSource(ioline_t _line) :
- line(_line)
- {}
- void DigitalSource::mode(uint8_t output)
- {
- palSetLineMode(line, output);
- }
- uint8_t DigitalSource::read()
- {
- return palReadLine(line);
- }
- void DigitalSource::write(uint8_t value)
- {
- palWriteLine(line, value);
- }
- void DigitalSource::toggle()
- {
- palToggleLine(line);
- }
- void pal_interrupt_cb(void *arg)
- {
- if (arg != nullptr) {
- ((AP_HAL::Proc)arg)();
- }
- }
- void pal_interrupt_cb_functor(void *arg)
- {
- const uint32_t now = AP_HAL::micros();
- struct gpio_entry *g = (gpio_entry *)arg;
- if (g == nullptr) {
-
- return;
- }
- if (!(g->fn)) {
- return;
- }
- (g->fn)(g->pin_num, palReadLine(g->pal_line), now);
- }
|