APM:Libraries
GPIO.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #include "GPIO.h"
18 
20 
21 #if HAL_USE_EXT == TRUE
22 
23 using namespace ChibiOS;
24 
25 // GPIO pin table from hwdef.dat
26 static struct gpio_entry {
27  uint8_t pin_num;
28  bool enabled;
29  uint8_t pwm_num;
30  ioline_t pal_line;
31  uint16_t port;
32 } _gpio_tab[] = HAL_GPIO_PINS;
33 
34 #define NUM_PINS ARRAY_SIZE_SIMPLE(_gpio_tab)
35 #define PIN_ENABLED(pin) ((pin)<NUM_PINS && _gpio_tab[pin].enabled)
36 
37 /*
38  map a user pin number to a GPIO table entry
39  */
40 static struct gpio_entry *gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
41 {
42  for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
43  if (pin_num == _gpio_tab[i].pin_num) {
44  if (check_enabled && !_gpio_tab[i].enabled) {
45  return NULL;
46  }
47  return &_gpio_tab[i];
48  }
49  }
50  return NULL;
51 }
52 
53 static void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel);
54 
55 static EXTConfig extcfg;
56 static AP_HAL::Proc ext_irq[EXT_MAX_CHANNELS]; // ext int irq list
57 
59 {}
60 
61 void GPIO::init()
62 {
63  // auto-disable pins being used for PWM output based on BRD_PWM_COUNT parameter
64  uint8_t pwm_count = AP_BoardConfig::get_pwm_count();
65  for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(_gpio_tab); i++) {
66  struct gpio_entry *g = &_gpio_tab[i];
67  if (g->pwm_num != 0) {
68  g->enabled = g->pwm_num > pwm_count;
69  }
70  }
71 }
72 
73 void GPIO::pinMode(uint8_t pin, uint8_t output)
74 {
75  struct gpio_entry *g = gpio_by_pin_num(pin);
76  if (g) {
77  palSetLineMode(g->pal_line, output);
78  }
79 }
80 
82 {
83  return -1;
84 }
85 
86 
87 uint8_t GPIO::read(uint8_t pin)
88 {
89  struct gpio_entry *g = gpio_by_pin_num(pin);
90  if (g) {
91  return palReadLine(g->pal_line);
92  }
93  return 0;
94 }
95 
96 void GPIO::write(uint8_t pin, uint8_t value)
97 {
98  struct gpio_entry *g = gpio_by_pin_num(pin);
99  if (g) {
100  if (value == PAL_LOW) {
101  palClearLine(g->pal_line);
102  } else {
103  palSetLine(g->pal_line);
104  }
105  }
106 }
107 
108 void GPIO::toggle(uint8_t pin)
109 {
110  struct gpio_entry *g = gpio_by_pin_num(pin);
111  if (g) {
112  palToggleLine(g->pal_line);
113  }
114 }
115 
116 /* Alternative interface: */
118 {
119  struct gpio_entry *g = gpio_by_pin_num(pin);
120  if (!g) {
121  return nullptr;
122  }
123  return new DigitalSource(g->pal_line);
124 }
125 
126 extern const AP_HAL::HAL& hal;
127 
128 /*
129  Attach an interrupt handler to ioline_t
130  */
131 bool GPIO::_attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
132 {
133  uint8_t pad = PAL_PAD(line);
134  stm32_gpio_t *pal_port = PAL_PORT(line);
135  uint8_t ext_port = 0xff;
136  const struct {
137  stm32_gpio_t *port;
138  uint8_t ext_port;
139  } port_mapping[] = {
140  { GPIOA, EXT_MODE_GPIOA },
141  { GPIOB, EXT_MODE_GPIOB },
142  { GPIOC, EXT_MODE_GPIOC },
143  { GPIOD, EXT_MODE_GPIOD },
144  { GPIOE, EXT_MODE_GPIOE },
145  { GPIOF, EXT_MODE_GPIOF },
146 #ifdef GPIOG
147  { GPIOG, EXT_MODE_GPIOG },
148 #endif
149 #ifdef GPIOH
150  { GPIOH, EXT_MODE_GPIOH },
151 #endif
152 #ifdef GPIOI
153  { GPIOI, EXT_MODE_GPIOI },
154 #endif
155  };
156  // convert the line to a EXT_MODE_GPIOn value, this is STM32 specific
157  for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(port_mapping); i++) {
158  if (pal_port == port_mapping[i].port) {
159  ext_port = port_mapping[i].ext_port;
160  }
161  }
162  if (ext_port == 0xff) {
163  return false;
164  }
165  if (p && ext_irq[pad] != nullptr && ext_irq[pad] != p) {
166  // already used
167  return false;
168  } else if (!p && !ext_irq[pad]) {
169  // nothing to remove
170  return false;
171  }
172  uint32_t chmode = 0;
173  switch(mode) {
175  chmode = EXT_CH_MODE_LOW_LEVEL;
176  break;
178  chmode = EXT_CH_MODE_FALLING_EDGE;
179  break;
181  chmode = EXT_CH_MODE_RISING_EDGE;
182  break;
184  chmode = EXT_CH_MODE_BOTH_EDGES;
185  break;
186  default:
187  if (p) {
188  return false;
189  }
190  break;
191  }
192  if (_ext_started) {
193  extStop(&EXTD1);
194  _ext_started = false;
195  }
196  extcfg.channels[pad].mode = chmode;
197  extcfg.channels[pad].mode |= (p?EXT_CH_MODE_AUTOSTART:0) | ext_port;
198  ext_irq[pad] = p;
199  extcfg.channels[pad].cb = ext_interrupt_cb;
200  extStart(&EXTD1, &extcfg);
201  _ext_started = true;
202  return true;
203 }
204 
205 /*
206  Attach an interrupt handler to a GPIO pin number. The pin number
207  must be one specified with a GPIO() marker in hwdef.dat
208  */
209 bool GPIO::attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode)
210 {
211  struct gpio_entry *g = gpio_by_pin_num(pin, false);
212  if (!g) {
213  return false;
214  }
215  return _attach_interrupt(g->pal_line, p, mode);
216 }
217 
219 {
220  return _usb_connected;
221 }
222 
224  line(_line)
225 {}
226 
227 void DigitalSource::mode(uint8_t output)
228 {
229  palSetLineMode(line, output);
230 }
231 
233 {
234  return palReadLine(line);
235 }
236 
238 {
239  palWriteLine(line, value);
240 }
241 
243 {
244  palToggleLine(line);
245 }
246 
247 void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
248 {
249  if (ext_irq[channel] != nullptr) {
250  ext_irq[channel]();
251  }
252 }
253 
254 #endif // HAL_USE_EXT
void pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:73
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t pin_num
Definition: GPIO.cpp:27
uint8_t pwm_num
Definition: GPIO.cpp:29
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
Definition: GPIO.cpp:209
DigitalSource(ioline_t line)
Definition: GPIO.cpp:223
#define HAL_GPIO_INTERRUPT_LOW
Definition: GPIO.h:10
uint16_t port
Definition: GPIO.cpp:31
bool enabled
Definition: GPIO.cpp:28
void write(uint8_t pin, uint8_t value)
Definition: GPIO.cpp:96
static struct gpio_entry * gpio_by_pin_num(uint8_t pin_num, bool check_enabled=true)
Definition: GPIO.cpp:40
#define HAL_GPIO_INTERRUPT_BOTH
Definition: GPIO.h:14
void(* Proc)(void)
Definition: GPIO.cpp:26
ioline_t pal_line
Definition: GPIO.cpp:30
static uint8_t get_pwm_count(void)
void init()
Definition: GPIO.cpp:61
static void ext_interrupt_cb(EXTDriver *extp, expchannel_t channel)
Definition: GPIO.cpp:247
int8_t analogPinToDigitalPin(uint8_t pin)
Definition: GPIO.cpp:81
void write(uint8_t value)
Definition: GPIO.cpp:237
AP_HAL::DigitalSource * channel(uint16_t n)
Definition: GPIO.cpp:117
#define HAL_GPIO_INTERRUPT_FALLING
Definition: GPIO.h:12
#define HAL_GPIO_INTERRUPT_RISING
Definition: GPIO.h:13
void mode(uint8_t output)
Definition: GPIO.cpp:227
bool _attach_interrupt(ioline_t line, AP_HAL::Proc p, uint8_t mode)
Definition: GPIO.cpp:131
static EXTConfig extcfg
Definition: GPIO.cpp:55
#define NULL
Definition: hal_types.h:59
bool usb_connected(void) override
Definition: GPIO.cpp:218
uint8_t read(uint8_t pin)
Definition: GPIO.cpp:87
ioline_t line
Definition: GPIO.h:67
void toggle(uint8_t pin)
Definition: GPIO.cpp:108
static struct gpio_entry _gpio_tab[]
float value
#define ARRAY_SIZE_SIMPLE(_arr)
Definition: AP_Common.h:83
static int8_t pin
Definition: AnalogIn.cpp:15
static AP_HAL::Proc ext_irq[EXT_MAX_CHANNELS]
Definition: GPIO.cpp:56