APM:Libraries
GPIO.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <stdint.h>
4 
5 #include "AP_HAL_Namespace.h"
6 
7 #define HAL_GPIO_INPUT 0
8 #define HAL_GPIO_OUTPUT 1
9 #define HAL_GPIO_ALT 2
10 #define HAL_GPIO_INTERRUPT_LOW 0
11 #define HAL_GPIO_INTERRUPT_HIGH 1
12 #define HAL_GPIO_INTERRUPT_FALLING 2
13 #define HAL_GPIO_INTERRUPT_RISING 3
14 #define HAL_GPIO_INTERRUPT_BOTH 4
15 
17 public:
18  virtual void mode(uint8_t output) = 0;
19  virtual uint8_t read() = 0;
20  virtual void write(uint8_t value) = 0;
21  virtual void toggle() = 0;
22 };
23 
24 class AP_HAL::GPIO {
25 public:
26  GPIO() {}
27  virtual void init() = 0;
28  virtual void pinMode(uint8_t pin, uint8_t output) = 0;
29 
30  // optional interface on some boards
31  virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt) {};
32 
33  virtual uint8_t read(uint8_t pin) = 0;
34  virtual void write(uint8_t pin, uint8_t value) = 0;
35  virtual void toggle(uint8_t pin) = 0;
36  virtual int8_t analogPinToDigitalPin(uint8_t pin) = 0;
37 
38  /* Alternative interface: */
39  virtual AP_HAL::DigitalSource* channel(uint16_t n) = 0;
40 
41  /* Interrupt interface: */
42  virtual bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
43  uint8_t mode) = 0;
44 
45  /* return true if USB cable is connected */
46  virtual bool usb_connected(void) = 0;
47 };
virtual void pinMode(uint8_t pin, uint8_t output, uint8_t alt)
Definition: GPIO.h:31
void(* Proc)(void)
virtual void mode(uint8_t output)=0
virtual void toggle()=0
static U8 usb_connected
Definition: usb.c:184
virtual uint8_t read()=0
void init()
Generic board initialization function.
Definition: system.cpp:136
float value
static int8_t pin
Definition: AnalogIn.cpp:15
GPIO()
Definition: GPIO.h:26
virtual void write(uint8_t value)=0