APM:Libraries
SPIDevice.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "SPIDevice.h"
18 
19 #include <assert.h>
20 #include <errno.h>
21 #include <fcntl.h>
22 #include <linux/spi/spidev.h>
23 #include <stdio.h>
24 #include <sys/ioctl.h>
25 #include <sys/stat.h>
26 #include <sys/types.h>
27 #include <unistd.h>
28 #include <vector>
29 
30 #include <AP_HAL/AP_HAL.h>
31 #include <AP_HAL/utility/OwnPtr.h>
32 
33 #include "GPIO.h"
34 #include "PollerThread.h"
35 #include "Scheduler.h"
36 #include "Semaphores.h"
37 #include "Thread.h"
38 #include "Util.h"
39 
40 namespace Linux {
41 
42 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
43 
44 #define MHZ (1000U*1000U)
45 #define KHZ (1000U)
46 #define SPI_CS_KERNEL -1
47 
48 struct SPIDesc {
49  SPIDesc(const char *name_, uint16_t bus_, uint16_t subdev_, uint8_t mode_,
50  uint8_t bits_per_word_, int16_t cs_pin_, uint32_t lowspeed_,
51  uint32_t highspeed_)
52  : name(name_), bus(bus_), subdev(subdev_), mode(mode_)
53  , bits_per_word(bits_per_word_), cs_pin(cs_pin_), lowspeed(lowspeed_)
54  , highspeed(highspeed_)
55  {
56  }
57 
58  const char *name;
59  uint16_t bus;
60  uint16_t subdev;
61  uint8_t mode;
62  uint8_t bits_per_word;
63  int16_t cs_pin;
64  uint32_t lowspeed;
65  uint32_t highspeed;
66 };
67 
68 
69 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
71  // different SPI tables per board subtype
72  SPIDesc("lsm9ds0_am", 1, 0, SPI_MODE_3, 8, BBB_P9_17, 10*MHZ,10*MHZ),
73  SPIDesc("lsm9ds0_g", 1, 0, SPI_MODE_3, 8, BBB_P8_9, 10*MHZ,10*MHZ),
74  SPIDesc("ms5611", 2, 0, SPI_MODE_3, 8, BBB_P9_42, 10*MHZ,10*MHZ),
75  SPIDesc("mpu6000", 2, 0, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
76  SPIDesc("mpu9250", 2, 0, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 11*MHZ),
77 };
78 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
79 SPIDesc SPIDeviceManager::_device[] = {
80  SPIDesc("mpu6000", 0, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 15*MHZ)
81 };
82 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
83 SPIDesc SPIDeviceManager::_device[] = {
84  SPIDesc("mpu9250", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
85  SPIDesc("ublox", 0, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 5*MHZ, 5*MHZ),
86 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2
87  SPIDesc("lsm9ds1_m", 0, 2, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
88 #endif
89 };
90 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
91  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
92 SPIDesc SPIDeviceManager::_device[] = {
93  SPIDesc("mpu9250", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
94  SPIDesc("ms5611", 0, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*KHZ, 10*MHZ),
95 };
96 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
97 SPIDesc SPIDeviceManager::_device[] = {
98  SPIDesc("mpu9250", 2, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
99  SPIDesc("mpu9250ext", 1, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
100  SPIDesc("ms5611", 2, 1, SPI_MODE_3, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
101 };
102 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
103 SPIDesc SPIDeviceManager::_device[] = {
104  SPIDesc("mpu9250", 1, 1, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
105  SPIDesc("bmp280", 1, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
106 };
107 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ
108 SPIDesc SPIDeviceManager::_device[] = {
109  /* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
110  SPIDesc("mpu9250", 1, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
111  SPIDesc("ms5611", 1, 1, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
112 };
113 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
114 SPIDesc SPIDeviceManager::_device[] = {
115  SPIDesc("mpu9250", 0, 0, SPI_MODE_0, 8, RPI_GPIO_7, 1*MHZ, 11*MHZ),
116  SPIDesc("ublox", 0, 0, SPI_MODE_0, 8, RPI_GPIO_8, 250*KHZ, 5*MHZ),
117 };
118 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK
119 SPIDesc SPIDeviceManager::_device[] = {
120  SPIDesc("mpu9250", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
121 };
122 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
123 SPIDesc SPIDeviceManager::_device[] = {
124  SPIDesc("bebop", 1, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 320*KHZ, 320*KHZ),
125 };
126 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO
127 SPIDesc SPIDeviceManager::_device[] = {
128  SPIDesc("aeroio", 1, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 10*MHZ, 10*MHZ),
129  SPIDesc("bmi160", 3, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
130 };
131 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_EDGE
132 SPIDesc SPIDeviceManager::_device[] = {
133  SPIDesc("mpu60x0", 0, 1, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
134  SPIDesc("mpu60x0ext", 0, 2, SPI_MODE_0, 8, SPI_CS_KERNEL, 1*MHZ, 11*MHZ),
135  SPIDesc("ms5611", 0, 0, SPI_MODE_0, 8, SPI_CS_KERNEL, 10*MHZ,10*MHZ),
136 };
137 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
138 SPIDesc SPIDeviceManager::_device[] = {
139  SPIDesc("rst_g", 0, 0, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
140  SPIDesc("lis3mdl", 0, 1, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
141  SPIDesc("rst_a", 0, 2, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
142  SPIDesc("ms5611", 0, 3, SPI_MODE_3, 8, SPI_CS_KERNEL, 1*MHZ, 10*MHZ),
143 };
144 #else
145 // empty device table
146 SPIDesc SPIDeviceManager::_device[] = {
147  SPIDesc("**dummy**", 0, 0, SPI_MODE_3, 0, 0, 0 * MHZ, 0 * MHZ),
148 };
149 #define LINUX_SPI_DEVICE_NUM_DEVICES 1
150 #endif
151 
152 #ifndef LINUX_SPI_DEVICE_NUM_DEVICES
153 #define LINUX_SPI_DEVICE_NUM_DEVICES ARRAY_SIZE(SPIDeviceManager::_device)
154 #endif
155 
157 
158 
159 /* Private struct to maintain for each bus */
161 public:
162  ~SPIBus();
163 
164  /*
165  * TimerPollable::WrapperCb methods to take
166  * and release semaphore while calling the callback
167  */
168  void start_cb() override;
169  void end_cb() override;
170 
171  int open(uint16_t bus_, uint16_t kernel_cs_);
172 
175  int fd = -1;
176  uint16_t bus;
177  uint16_t kernel_cs;
178  uint8_t ref;
179  int16_t last_mode = -1;
180 };
181 
183 {
184  if (fd >= 0) {
185  ::close(fd);
186  }
187 }
188 
190 {
191  sem.take(HAL_SEMAPHORE_BLOCK_FOREVER);
192 }
193 
195 {
196  sem.give();
197 }
198 
199 
200 int SPIBus::open(uint16_t bus_, uint16_t kernel_cs_)
201 {
202  char path[sizeof("/dev/spidevXXXXX.XXXXX")];
203 
204  if (fd > 0) {
205  return -EBUSY;
206  }
207 
208  snprintf(path, sizeof(path), "/dev/spidev%u.%u", bus_, kernel_cs_);
209  fd = ::open(path, O_RDWR | O_CLOEXEC);
210  if (fd < 0) {
211  AP_HAL::panic("SPI: unable to open SPI bus %s: %s",
212  path, strerror(errno));
213  }
214 
215  bus = bus_;
216  kernel_cs = kernel_cs_;
217 
218  return fd;
219 }
220 
221 
223  : _bus(bus)
224  , _desc(device_desc)
225 {
229 
230  if (_desc.cs_pin != SPI_CS_KERNEL) {
231  _cs = hal.gpio->channel(_desc.cs_pin);
232  if (!_cs) {
233  AP_HAL::panic("Unable to instantiate cs pin");
234  }
235 
237 
238  // do not hold the SPI bus initially
239  _cs_release();
240  }
241 }
242 
244 {
245  // Unregister itself from the SPIDeviceManager
247 }
248 
250 {
251  switch (speed) {
254  break;
257  break;
258  }
259 
260  return true;
261 }
262 
263 bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
264  uint8_t *recv, uint32_t recv_len)
265 {
266  struct spi_ioc_transfer msgs[2] = { };
267  unsigned nmsgs = 0;
268 
269  assert(_bus.fd >= 0);
270 
271  if (send && send_len != 0) {
272  msgs[nmsgs].tx_buf = (uint64_t) send;
273  msgs[nmsgs].rx_buf = 0;
274  msgs[nmsgs].len = send_len;
275  msgs[nmsgs].speed_hz = _speed;
276  msgs[nmsgs].delay_usecs = 0;
277  msgs[nmsgs].bits_per_word = _desc.bits_per_word;
278  msgs[nmsgs].cs_change = 0;
279  nmsgs++;
280  }
281 
282  if (recv && recv_len != 0) {
283  msgs[nmsgs].tx_buf = 0;
284  msgs[nmsgs].rx_buf = (uint64_t) recv;
285  msgs[nmsgs].len = recv_len;
286  msgs[nmsgs].speed_hz = _speed;
287  msgs[nmsgs].delay_usecs = 0;
288  msgs[nmsgs].bits_per_word = _desc.bits_per_word;
289  msgs[nmsgs].cs_change = 0;
290  nmsgs++;
291  }
292 
293  if (!nmsgs) {
294  return false;
295  }
296 
297  int r;
298  if (_bus.last_mode == _desc.mode) {
299  /*
300  the mode in the kernel is not tied to the file descriptor,
301  so there is a chance some other process has changed it since
302  we last used the bus. We want to report when this happens so
303  the user has a chance of figuring out when there is
304  conflicted use of the SPI bus. Unfortunately this costs us
305  an extra syscall per transfer.
306  */
307  uint8_t current_mode;
308  if (ioctl(_bus.fd, SPI_IOC_RD_MODE, &current_mode) < 0) {
309  hal.console->printf("SPIDevice: error on getting mode fd=%d (%s)\n",
310  _bus.fd, strerror(errno));
311  _bus.last_mode = -1;
312  } else if (current_mode != _bus.last_mode) {
313  hal.console->printf("SPIDevice: bus mode conflict fd=%d mode=%u/%u\n",
314  _bus.fd, (unsigned)_bus.last_mode, (unsigned)current_mode);
315  _bus.last_mode = -1;
316  }
317  }
318  if (_desc.mode != _bus.last_mode) {
319  r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode);
320  if (r < 0) {
321  hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
322  _bus.fd, strerror(errno));
323  return false;
324  }
326  }
327 
328  _cs_assert();
329  r = ioctl(_bus.fd, SPI_IOC_MESSAGE(nmsgs), &msgs);
330  _cs_release();
331 
332  if (r == -1) {
333  hal.console->printf("SPIDevice: error transferring data fd=%d (%s)\n",
334  _bus.fd, strerror(errno));
335  return false;
336  }
337 
338  return true;
339 }
340 
341 bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv,
342  uint32_t len)
343 {
344  struct spi_ioc_transfer msgs[1] = { };
345 
346  assert(_bus.fd >= 0);
347 
348  if (!send || !recv || len == 0) {
349  return false;
350  }
351 
352  msgs[0].tx_buf = (uint64_t) send;
353  msgs[0].rx_buf = (uint64_t) recv;
354  msgs[0].len = len;
355  msgs[0].speed_hz = _speed;
356  msgs[0].delay_usecs = 0;
357  msgs[0].bits_per_word = _desc.bits_per_word;
358  msgs[0].cs_change = 0;
359 
360  int r = ioctl(_bus.fd, SPI_IOC_WR_MODE, &_desc.mode);
361  if (r < 0) {
362  hal.console->printf("SPIDevice: error on setting mode fd=%d (%s)\n",
363  _bus.fd, strerror(errno));
364  return false;
365  }
366 
367  _cs_assert();
368  r = ioctl(_bus.fd, SPI_IOC_MESSAGE(1), &msgs);
369  _cs_release();
370 
371  if (r == -1) {
372  hal.console->printf("SPIDevice: error transferring data fd=%d (%s)\n",
373  _bus.fd, strerror(errno));
374  return false;
375  }
376 
377  return true;
378 }
379 
380 
382 {
383  if (_desc.cs_pin == SPI_CS_KERNEL) {
384  return;
385  }
386 
387  _cs->write(0);
388 }
389 
391 {
392  if (_desc.cs_pin == SPI_CS_KERNEL) {
393  return;
394  }
395 
396  _cs->write(1);
397 }
398 
400 {
401  return &_bus.sem;
402 }
403 
405  uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
406 {
407  TimerPollable *p = _bus.thread.add_timer(cb, &_bus, period_usec);
408  if (!p) {
409  AP_HAL::panic("Could not create periodic callback");
410  }
411 
412  if (!_bus.thread.is_started()) {
413  char name[16];
414  snprintf(name, sizeof(name), "ap-spi-%u", _bus.bus);
415 
419  }
420 
421  return static_cast<AP_HAL::Device::PeriodicHandle>(p);
422 }
423 
425  AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
426 {
427  return _bus.thread.adjust_timer(static_cast<TimerPollable*>(h), period_usec);
428 }
429 
430 
433 {
434  SPIDesc *desc = nullptr;
435 
436  /* Find the bus description in the table */
437  for (uint8_t i = 0; i < _n_device_desc; i++) {
438  if (!strcmp(_device[i].name, name)) {
439  desc = &_device[i];
440  break;
441  }
442  }
443 
444  if (!desc) {
445  printf("SPI: Invalid device name: %s\n", name);
446  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
447  }
448 
449  /* Find if bus is already open */
450  for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
451  if (_buses[i]->bus == desc->bus &&
452  _buses[i]->kernel_cs == desc->subdev) {
453  return _create_device(*_buses[i], *desc);
454  }
455  }
456 
457  /* Bus not found for this device, create a new one */
459  if (!b || b->open(desc->bus, desc->subdev) < 0) {
460  return nullptr;
461  }
462 
463  auto dev = _create_device(*b, *desc);
464  if (!dev) {
465  return nullptr;
466  }
467 
468  _buses.push_back(b.leak());
469 
470  return dev;
471 }
472 
474  return _n_device_desc;
475 }
476 
477 const char* SPIDeviceManager::get_device_name(uint8_t idx)
478 {
479  return _device[idx].name;
480 }
481 
482 /* Create a new device increasing the bus reference */
485 {
486  auto dev = AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(b, desc));
487  if (!dev) {
488  return nullptr;
489  }
490  b.ref++;
491  return dev;
492 }
493 
495 {
496  if (b.ref == 0 || --b.ref > 0) {
497  return;
498  }
499 
500  for (auto it = _buses.begin(); it != _buses.end(); it++) {
501  if ((*it)->bus == b.bus && (*it)->kernel_cs == b.kernel_cs) {
502  _buses.erase(it);
503  delete &b;
504  break;
505  }
506  }
507 }
508 
510 {
511  for (auto it = _buses.begin(); it != _buses.end(); it++) {
512  /* Try to stop thread - it may not even be started yet */
513  (*it)->thread.stop();
514  }
515 
516  for (auto it = _buses.begin(); it != _buses.end(); it++) {
517  /* Try to join thread - failing is normal if thread was not started */
518  (*it)->thread.join();
519  }
520 }
521 
522 }
int printf(const char *fmt,...)
Definition: stdio.c:113
#define KHZ
Definition: SPIDevice.cpp:45
int open(uint16_t bus_, uint16_t kernel_cs_)
Definition: SPIDevice.cpp:200
static SPIDeviceManager * from(AP_HAL::SPIDeviceManager *spi_mgr)
Definition: SPIDevice.h:81
AP_HAL::Semaphore * get_semaphore() override
Definition: SPIDevice.cpp:399
uint16_t subdev
Definition: SPIDevice.cpp:60
static SPIDesc _device[]
Definition: SPIDevice.h:115
int16_t last_mode
Definition: SPIDevice.cpp:179
Definition: spi.h:55
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
static const uint8_t _n_device_desc
Definition: SPIDevice.h:114
uint16_t bus
Definition: SPIDevice.cpp:176
AP_HAL::UARTDriver * console
Definition: HAL.h:110
SPIBus & _bus
Definition: SPIDevice.h:61
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:249
void set_device_bus(uint8_t bus)
Definition: Device.h:291
#define BBB_P9_42
Definition: GPIO_BBB.h:108
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
Definition: SPIDevice.cpp:341
uint8_t mode
Definition: SPIDevice.cpp:61
bool adjust_timer(TimerPollable *p, uint32_t timeout_usec)
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
uint32_t lowspeed
Definition: SPIDevice.cpp:64
Semaphore sem
Definition: SPIDevice.cpp:174
#define BBB_P8_9
Definition: GPIO_BBB.h:48
const char * name
Definition: BusTest.cpp:11
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _create_device(SPIBus &b, SPIDesc &device_desc) const
Definition: SPIDevice.cpp:484
SPIDesc & _desc
Definition: SPIDevice.h:62
uint8_t bits_per_word
Definition: SPIDevice.cpp:62
virtual void mode(uint8_t output)=0
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: SPIDevice.cpp:424
bool is_started() const
Definition: Thread.h:42
const char * get_device_name(uint8_t idx)
Definition: SPIDevice.cpp:477
SPIDesc(const char *name_, uint16_t bus_, uint16_t subdev_, uint8_t mode_, uint8_t bits_per_word_, int16_t cs_pin_, uint32_t lowspeed_, uint32_t highspeed_)
Definition: SPIDevice.cpp:49
uint16_t bus
Definition: SPIDevice.cpp:59
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:263
uint32_t highspeed
Definition: SPIDevice.cpp:65
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define RPI_GPIO_7
Definition: GPIO_RPI.h:18
#define LINUX_SPI_DEVICE_NUM_DEVICES
Definition: SPIDevice.cpp:153
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
void * PeriodicHandle
Definition: Device.h:42
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
#define RPI_GPIO_8
Definition: GPIO_RPI.h:19
virtual AP_HAL::DigitalSource * channel(uint16_t n)=0
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: SPIDevice.cpp:404
uint32_t _speed
Definition: SPIDevice.h:64
Definition: spi.h:61
#define SPI_CS_KERNEL
Definition: SPIDevice.cpp:46
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
AP_HAL::DigitalSource * _cs
Definition: SPIDevice.h:63
#define HAL_GPIO_OUTPUT
Definition: GPIO.h:8
const HAL & get_HAL()
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
Definition: SPIDevice.cpp:432
#define AP_LINUX_SENSORS_SCHED_PRIO
Definition: Scheduler.h:15
PollerThread thread
Definition: SPIDevice.cpp:173
TimerPollable * add_timer(TimerPollable::PeriodicCb cb, TimerPollable::WrapperCb *wrapper, uint32_t timeout_usec)
const char * name
Definition: SPIDevice.cpp:58
#define AP_LINUX_SENSORS_STACK_SIZE
Definition: Scheduler.h:13
bool set_stack_size(size_t stack_size)
Definition: Thread.cpp:236
void end_cb() override
Definition: SPIDevice.cpp:194
void _unregister(SPIBus &b)
Definition: SPIDevice.cpp:494
AP_HAL::GPIO * gpio
Definition: HAL.h:111
#define BBB_P9_17
Definition: GPIO_BBB.h:92
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
virtual ~SPIDevice()
Definition: SPIDevice.cpp:243
bool start(const char *name, int policy, int prio)
Definition: Thread.cpp:155
int16_t cs_pin
Definition: SPIDevice.cpp:63
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define AP_LINUX_SENSORS_SCHED_POLICY
Definition: Scheduler.h:14
uint16_t kernel_cs
Definition: SPIDevice.cpp:177
#define BBB_P9_23
Definition: GPIO_BBB.h:98
void set_device_address(uint8_t address)
Definition: Device.h:286
#define BBB_P9_28
Definition: GPIO_BBB.h:103
void start_cb() override
Definition: SPIDevice.cpp:189
#define MHZ
Definition: SPIDevice.cpp:44
virtual void write(uint8_t value)=0