APM:Libraries
GPIO_RPI.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
4  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
5  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
6  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
7 
8 #include <errno.h>
9 #include <fcntl.h>
10 #include <poll.h>
11 #include <stdio.h>
12 #include <stdlib.h>
13 #include <string.h>
14 #include <sys/mman.h>
15 #include <sys/stat.h>
16 #include <unistd.h>
17 
18 #include "GPIO.h"
19 #include "Util_RPI.h"
20 
21 // Raspberry Pi GPIO memory
22 #define BCM2708_PERI_BASE 0x20000000
23 #define BCM2709_PERI_BASE 0x3F000000
24 #define GPIO_BASE(address) (address + 0x200000)
25 
26 // GPIO setup. Always use INP_GPIO(x) before OUT_GPIO(x) or SET_GPIO_ALT(x,y)
27 #define GPIO_MODE_IN(g) *(_gpio+((g)/10)) &= ~(7<<(((g)%10)*3))
28 #define GPIO_MODE_OUT(g) *(_gpio+((g)/10)) |= (1<<(((g)%10)*3))
29 #define GPIO_MODE_ALT(g,a) *(_gpio+(((g)/10))) |= (((a)<=3?(a)+4:(a)==4?3:2)<<(((g)%10)*3))
30 #define GPIO_SET_HIGH *(_gpio+7) // sets bits which are 1
31 #define GPIO_SET_LOW *(_gpio+10) // clears bits which are 1
32 #define GPIO_GET(g) (*(_gpio+13)&(1<<g)) // 0 if LOW, (1<<g) if HIGH
33 
34 using namespace Linux;
35 
36 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
37 
39 {
40 }
41 
43 {
44  int rpi_version = UtilRPI::from(hal.util)->get_rpi_version();
45  uint32_t gpio_address = rpi_version == 1 ? GPIO_BASE(BCM2708_PERI_BASE) : GPIO_BASE(BCM2709_PERI_BASE);
46 
47  int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
48  if (mem_fd < 0) {
49  AP_HAL::panic("Can't open /dev/mem");
50  }
51 
52  // mmap GPIO
53  void *gpio_map = mmap(
54  nullptr, // Any adddress in our space will do
55  BLOCK_SIZE, // Map length
56  PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
57  MAP_SHARED, // Shared with other processes
58  mem_fd, // File to map
59  gpio_address // Offset to GPIO peripheral
60  );
61 
62  close(mem_fd); // No need to keep mem_fd open after mmap
63 
64  if (gpio_map == MAP_FAILED) {
65  AP_HAL::panic("Can't open /dev/mem");
66  }
67 
68  _gpio = (volatile uint32_t *)gpio_map;
69 }
70 
71 void GPIO_RPI::pinMode(uint8_t pin, uint8_t output)
72 {
73  if (output == HAL_GPIO_INPUT) {
74  GPIO_MODE_IN(pin);
75  } else {
76  GPIO_MODE_IN(pin);
77  GPIO_MODE_OUT(pin);
78  }
79 }
80 
81 void GPIO_RPI::pinMode(uint8_t pin, uint8_t output, uint8_t alt)
82 {
83  if (output == HAL_GPIO_INPUT) {
84  GPIO_MODE_IN(pin);
85  } else if (output == HAL_GPIO_ALT) {
86  GPIO_MODE_IN(pin);
87  GPIO_MODE_ALT(pin, alt);
88  } else {
89  GPIO_MODE_IN(pin);
90  GPIO_MODE_OUT(pin);
91  }
92 }
93 
95 {
96  return -1;
97 }
98 
99 uint8_t GPIO_RPI::read(uint8_t pin)
100 {
101  uint32_t value = GPIO_GET(pin);
102  return value ? 1: 0;
103 }
104 
105 void GPIO_RPI::write(uint8_t pin, uint8_t value)
106 {
107  if (value == LOW) {
108  GPIO_SET_LOW = 1 << pin;
109  } else {
110  GPIO_SET_HIGH = 1 << pin;
111  }
112 }
113 
114 void GPIO_RPI::toggle(uint8_t pin)
115 {
116  write(pin, !read(pin));
117 }
118 
119 /* Alternative interface: */
121 {
122  return new DigitalSource(n);
123 }
124 
125 /* Interrupt interface: */
126 bool GPIO_RPI::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
127 {
128  return true;
129 }
130 
132 {
133  return false;
134 }
135 
136 #endif
#define BCM2709_PERI_BASE
Definition: GPIO_RPI.cpp:23
bool usb_connected(void)
Definition: GPIO_RPI.cpp:131
#define GPIO_MODE_IN(g)
Definition: GPIO_RPI.cpp:27
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::Util * util
Definition: HAL.h:115
void(* Proc)(void)
AP_HAL::DigitalSource * channel(uint16_t n)
Definition: GPIO_RPI.cpp:120
#define GPIO_GET(g)
Definition: GPIO_RPI.cpp:32
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)
Definition: GPIO_RPI.cpp:126
#define GPIO_BASE(address)
Definition: GPIO_RPI.cpp:24
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
#define GPIO_MODE_ALT(g, a)
Definition: GPIO_RPI.cpp:29
#define BCM2708_PERI_BASE
Definition: GPIO_RPI.cpp:22
void pinMode(uint8_t pin, uint8_t output)
Definition: GPIO_RPI.cpp:71
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
int8_t analogPinToDigitalPin(uint8_t pin)
Definition: GPIO_RPI.cpp:94
#define LOW
Definition: board.h:31
void toggle(uint8_t pin)
Definition: GPIO_RPI.cpp:114
#define GPIO_MODE_OUT(g)
Definition: GPIO_RPI.cpp:28
#define BLOCK_SIZE
Definition: GPIO_RPI.h:10
void write(uint8_t pin, uint8_t value)
Definition: GPIO_RPI.cpp:105
const HAL & get_HAL()
#define HAL_GPIO_INPUT
Definition: GPIO.h:7
int get_rpi_version() const
Definition: Util_RPI.cpp:74
static UtilRPI * from(AP_HAL::Util *util)
Definition: Util_RPI.h:11
#define GPIO_SET_LOW
Definition: GPIO_RPI.cpp:31
float value
volatile uint32_t * _gpio
Definition: GPIO_RPI.h:68
#define HAL_GPIO_ALT
Definition: GPIO.h:9
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static int8_t pin
Definition: AnalogIn.cpp:15
#define GPIO_SET_HIGH
Definition: GPIO_RPI.cpp:30
uint8_t read(uint8_t pin)
Definition: GPIO_RPI.cpp:99