/* * 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 . * * Code by Andrew Tridgell and Siddharth Bharat Purohit */ #include "GPIO.h" #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include using namespace ChibiOS; // GPIO pin table from hwdef.dat static struct gpio_entry { uint8_t pin_num; bool enabled; uint8_t pwm_num; ioline_t pal_line; } _gpio_tab[] = HAL_GPIO_PINS; #define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab) #define PIN_ENABLED(pin) ((pin)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) { palSetLineMode(g->pal_line, output); } } int8_t GPIO::analogPinToDigitalPin(uint8_t pin) { return -1; } 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 (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); } } /* Alternative interface: */ AP_HAL::DigitalSource* GPIO::channel(uint16_t n) { return new DigitalSource(0); } /* Interrupt interface: */ bool GPIO::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode) { 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; } bool GPIO::usb_connected(void) { return _usb_connected; } DigitalSource::DigitalSource(uint8_t v) : _v(v) {} void DigitalSource::mode(uint8_t output) {} uint8_t DigitalSource::read() { return _v; } void DigitalSource::write(uint8_t value) { _v = value; } void DigitalSource::toggle() { _v = !_v; } void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel) { if (ext_irq[channel] != nullptr) { ext_irq[channel](); } } #endif //HAL_BOARD_ChibiOS