/* * 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" #include #if HAL_USE_EXT == TRUE 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; uint16_t port; } _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 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; /* Attach an interrupt handler to ioline_t */ bool GPIO::_attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode) { uint8_t pad = PAL_PAD(line); stm32_gpio_t *pal_port = PAL_PORT(line); uint8_t ext_port = 0xff; const struct { stm32_gpio_t *port; uint8_t ext_port; } port_mapping[] = { { GPIOA, EXT_MODE_GPIOA }, { GPIOB, EXT_MODE_GPIOB }, { GPIOC, EXT_MODE_GPIOC }, { GPIOD, EXT_MODE_GPIOD }, { GPIOE, EXT_MODE_GPIOE }, { GPIOF, EXT_MODE_GPIOF }, #ifdef GPIOG { GPIOG, EXT_MODE_GPIOG }, #endif #ifdef GPIOH { GPIOH, EXT_MODE_GPIOH }, #endif #ifdef GPIOI { GPIOI, EXT_MODE_GPIOI }, #endif }; // convert the line to a EXT_MODE_GPIOn value, this is STM32 specific for (uint8_t i=0; ipal_line, p, mode); } 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 ext_interrupt_cb(EXTDriver *extp, expchannel_t channel) { if (ext_irq[channel] != nullptr) { ext_irq[channel](); } } #endif // HAL_USE_EXT