APM:Libraries
GPIO_Sysfs.cpp
Go to the documentation of this file.
1 #include "GPIO_Sysfs.h"
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #include <fcntl.h>
6 #include <stdio.h>
7 #include <sys/stat.h>
8 #include <unistd.h>
9 
10 #include "Util.h"
11 
12 #define LOW 0
13 #define HIGH 1
14 #define assert_vpin(v_, max_, ...) do { \
15  if (v_ >= max_) { \
16  hal.console->printf("warning (%s): vpin %u out of range [0, %u)\n",\
17  __PRETTY_FUNCTION__, v_, max_); \
18  return __VA_ARGS__; \
19  } \
20  } while (0)
21 
22 using namespace Linux;
23 
24 static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
25 
26 #define UINT32_MAX_STR "4294967295"
27 
28 /* Trick to use minimum stack space for each of the params */
29 union gpio_params {
30  char export_gpio[sizeof("export")];
31  char direction[sizeof("gpio" UINT32_MAX_STR "/direction")];
32  char value[sizeof("gpio" UINT32_MAX_STR "/value")];
33 };
34 
35 #define GPIO_BASE_PATH "/sys/class/gpio/"
36 #define GPIO_PATH_MAX (sizeof(GPIO_BASE_PATH) + sizeof(gpio_params) - 1)
37 
39  : _pin(pin)
40  , _value_fd(value_fd)
41 {
42 }
43 
45 {
46  if (_value_fd >= 0) {
48  }
49 }
50 
52 {
53  char char_value;
54  if (::pread(_value_fd, &char_value, 1, 0) < 0) {
55  hal.console->printf("DigitalSource_Sysfs: Unable to read pin %u value.\n",
56  _pin);
57  return LOW;
58  }
59  return char_value - '0';
60 }
61 
63 {
64  if (::pwrite(_value_fd, value == HIGH ? "1" : "0", 1, 0) < 0) {
65  hal.console->printf("DigitalSource_Sysfs: Unable to write pin %u value.\n",
66  _pin);
67  }
68 }
69 
70 void DigitalSource_Sysfs::mode(uint8_t output)
71 {
72  auto gpio_sysfs = GPIO_Sysfs::from(hal.gpio);
73  gpio_sysfs->_pinMode(_pin, output);
74 }
75 
77 {
78  write(!read());
79 }
80 
82 {
83 }
84 
85 void GPIO_Sysfs::pinMode(uint8_t vpin, uint8_t output)
86 {
87  assert_vpin(vpin, n_pins);
88 
89  _export_pin(vpin);
90  _pinMode(pin_table[vpin], output);
91 }
92 
93 void GPIO_Sysfs::_pinMode(unsigned int pin, uint8_t output)
94 {
95  const char *dir = output ? "out" : "in";
96  char path[GPIO_PATH_MAX];
97 
98  int r = snprintf(path, GPIO_PATH_MAX, GPIO_BASE_PATH "gpio%u/direction",
99  pin);
100  if (r < 0 || r >= (int)GPIO_PATH_MAX
101  || Util::from(hal.util)->write_file(path, "%s", dir) < 0) {
102  hal.console->printf("GPIO_Sysfs: Unable to set pin %u mode.\n", pin);
103  }
104 }
105 
106 int GPIO_Sysfs::_open_pin_value(unsigned int pin, int flags)
107 {
108  char path[GPIO_PATH_MAX];
109  int fd;
110 
111  int r = snprintf(path, GPIO_PATH_MAX, GPIO_BASE_PATH "gpio%u/value", pin);
112  if (r < 0 || r >= (int)GPIO_PATH_MAX
113  || (fd = open(path, flags | O_CLOEXEC)) < 0) {
114  hal.console->printf("GPIO_Sysfs: Unable to get value file descriptor for pin %u.\n",
115  pin);
116  return -1;
117  }
118 
119  return fd;
120 }
121 
122 uint8_t GPIO_Sysfs::read(uint8_t vpin)
123 {
124  assert_vpin(vpin, n_pins, LOW);
125 
126  const unsigned pin = pin_table[vpin];
127  int fd = _open_pin_value(pin, O_RDONLY);
128 
129  if (fd < 0) {
130  goto error;
131  }
132 
133  char char_value;
134  if (::pread(fd, &char_value, 1, 0) < 0) {
135  goto error;
136  }
137 
138  close(fd);
139 
140  return char_value - '0';
141 
142 error:
143  hal.console->printf("GPIO_Sysfs: Unable to read pin %u value.\n", vpin);
144  return LOW;
145 }
146 
147 void GPIO_Sysfs::write(uint8_t vpin, uint8_t value)
148 {
149  assert_vpin(vpin, n_pins);
150 
151  const unsigned pin = pin_table[vpin];
152  int fd = _open_pin_value(pin, O_WRONLY);
153 
154  if (fd < 0) {
155  goto error;
156  }
157 
158  if (::pwrite(fd, value == HIGH ? "1" : "0", 1, 0) < 0) {
159  goto error;
160  }
161 
162  close(fd);
163  return;
164 
165 error:
166  hal.console->printf("GPIO_Sysfs: Unable to write pin %u value.\n", vpin);
167 }
168 
169 void GPIO_Sysfs::toggle(uint8_t vpin)
170 {
171  write(vpin, !read(vpin));
172 }
173 
175 {
176  return -1;
177 }
178 
180 {
181  assert_vpin(vpin, n_pins, nullptr);
182 
183  const unsigned pin = pin_table[vpin];
184  int value_fd = -1;
185 
186  if (_export_pin(vpin)) {
187  value_fd = _open_pin_value(pin, O_RDWR);
188  }
189 
190  /* Even if we couldn't open the fd, return a new DigitalSource and let
191  * reads and writes fail later due to invalid. Otherwise we
192  * could crash in undesired places */
193  return new DigitalSource_Sysfs(pin, value_fd);
194 }
195 
196 bool GPIO_Sysfs::attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p,
197  uint8_t mode)
198 {
199  return false;
200 }
201 
203 {
204  return false;
205 }
206 
207 bool GPIO_Sysfs::_export_pin(uint8_t vpin)
208 {
209  assert_vpin(vpin, n_pins, false);
210 
211  const unsigned int pin = pin_table[vpin];
212  char gpio_path[GPIO_PATH_MAX];
213  int fd;
214 
215  int r = snprintf(gpio_path, GPIO_PATH_MAX, GPIO_BASE_PATH "gpio%u", pin);
216  if (r < 0 || r >= (int) GPIO_PATH_MAX) {
217  goto fail_snprintf;
218  }
219 
220  if (access(gpio_path, F_OK) == 0) {
221  // Already exported
222  return true;
223  }
224 
225  fd = open(GPIO_BASE_PATH "export", O_WRONLY | O_CLOEXEC);
226  if (fd < 0) {
227  goto fail_open;
228  }
229 
230  // Try to export
231  if (dprintf(fd, "%u", pin) < 0) {
232  goto fail_export;
233  }
234 
235  close(fd);
236  return true;
237 
238 fail_export:
239  close(fd);
240 fail_open:
241 fail_snprintf:
242  hal.console->printf("GPIO_Sysfs: Unable to export pin %u.\n", pin);
243  return false;
244 }
AP_HAL::DigitalSource * channel(uint16_t vpin) override
Definition: GPIO_Sysfs.cpp:179
void toggle(uint8_t vpin) override
Definition: GPIO_Sysfs.cpp:169
static bool _export_pin(uint8_t vpin)
Definition: GPIO_Sysfs.cpp:207
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define assert_vpin(v_, max_,...)
Definition: GPIO_Sysfs.cpp:14
bool usb_connected() override
Definition: GPIO_Sysfs.cpp:202
#define LOW
Definition: GPIO_Sysfs.cpp:12
static GPIO_Sysfs * from(AP_HAL::GPIO *gpio)
Definition: GPIO_Sysfs.h:35
AP_HAL::Util * util
Definition: HAL.h:115
DigitalSource_Sysfs(unsigned pin, int value_fd)
Definition: GPIO_Sysfs.cpp:38
void(* Proc)(void)
#define HIGH
Definition: GPIO_Sysfs.cpp:13
void write(uint8_t value)
Definition: GPIO_Sysfs.cpp:62
#define UINT32_MAX_STR
Definition: GPIO_Sysfs.cpp:26
static Util * from(AP_HAL::Util *util)
Definition: Util.h:27
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
void pinMode(uint8_t vpin, uint8_t output) override
Definition: GPIO_Sysfs.cpp:85
uint8_t read(uint8_t vpin) override
Definition: GPIO_Sysfs.cpp:122
void mode(uint8_t output)
Definition: GPIO_Sysfs.cpp:70
const HAL & get_HAL()
AP_HAL::GPIO * gpio
Definition: HAL.h:111
int write_file(const char *path, const char *fmt,...) FMT_PRINTF(3
Definition: Util.cpp:126
bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode) override
Definition: GPIO_Sysfs.cpp:196
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
#define error(fmt, args ...)
int _open_pin_value(unsigned int pin, int flags)
Definition: GPIO_Sysfs.cpp:106
void write(uint8_t vpin, uint8_t value) override
Definition: GPIO_Sysfs.cpp:147
float value
static int8_t pin
Definition: AnalogIn.cpp:15
int8_t analogPinToDigitalPin(uint8_t vpin) override
Definition: GPIO_Sysfs.cpp:174
#define GPIO_PATH_MAX
Definition: GPIO_Sysfs.cpp:36
void _pinMode(unsigned int pin, uint8_t output)
Definition: GPIO_Sysfs.cpp:93
#define GPIO_BASE_PATH
Definition: GPIO_Sysfs.cpp:35