APM:Libraries
SPIUARTDriver.cpp
Go to the documentation of this file.
1 #include "SPIUARTDriver.h"
2 
3 #include <assert.h>
4 #include <stdlib.h>
5 #include <cstdio>
6 
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 
10 extern const AP_HAL::HAL &hal;
11 
12 #ifdef SPIUART_DEBUG
13 #include <stdio.h>
14 #define debug(fmt, args ...) do {hal.console->printf("[SPIUARTDriver]: %s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
15 #define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
16 #else
17 #define debug(fmt, args ...)
18 #define error(fmt, args ...)
19 #endif
20 
21 using namespace Linux;
22 
24  : UARTDriver(false)
25 {
26 }
27 
28 void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
29 {
30  if (device_path != nullptr) {
31  UARTDriver::begin(b, rxS, txS);
32  if (is_initialized()) {
33  _external = true;
34  return;
35  }
36  }
37 
38  if (!is_initialized()) {
39  _dev = hal.spi->get_device("ublox");
40  if (!_dev) {
41  return;
42  }
43  }
44 
45  if (rxS < 1024) {
46  rxS = 2048;
47  }
48  if (txS < 1024) {
49  txS = 2048;
50  }
51 
52  _readbuf.set_size(rxS);
53  _writebuf.set_size(txS);
54 
55  if (_buffer == nullptr) {
56  /* Do not allocate new buffer, if we're just changing speed */
57  _buffer = new uint8_t[rxS];
58  if (_buffer == nullptr) {
59  hal.console->printf("Not enough memory\n");
60  AP_HAL::panic("Not enough memory\n");
61  }
62  }
63 
64  switch (b) {
65  case 4000000U:
66  if (is_initialized()) {
67  /* Do not allow speed changes before device is initialized, because
68  * it can lead to misconfiguraration. Once the device is initialized,
69  * it's sage to update speed
70  */
72  debug("Set higher SPI-frequency");
73  } else {
75  debug("Set lower SPI-frequency");
76  }
77  break;
78  default:
80  debug("Set lower SPI-frequency");
81  debug("%s: wrong baudrate (%u) for SPI-driven device. setting default speed", __func__, b);
82  break;
83  }
84 
85  _initialised = true;
86 }
87 
88 int SPIUARTDriver::_write_fd(const uint8_t *buf, uint16_t size)
89 {
90  if (_external) {
91  return UARTDriver::_write_fd(buf,size);
92  }
93 
94  if (!_dev->get_semaphore()->take_nonblocking()) {
95  return 0;
96  }
97 
98  _dev->transfer_fullduplex(buf, _buffer, size);
99 
100  _dev->get_semaphore()->give();
101 
102  uint16_t ret = size;
103 
104  /* Since all SPI-transactions are transfers we need update
105  * the _readbuf. I do believe there is a way to encapsulate
106  * this operation since it's the same as in the
107  * UARTDriver::write().
108  */
109  _readbuf.write(_buffer, size);
110 
111  return ret;
112 }
113 
114 int SPIUARTDriver::_read_fd(uint8_t *buf, uint16_t n)
115 {
116  static uint8_t ff_stub[100] = {0xff};
117 
118  if (_external) {
119  return UARTDriver::_read_fd(buf, n);
120  }
121 
122  /* Make SPI transactions shorter. It can save SPI bus from keeping too
123  * long. It's essential for NavIO as MPU9250 is on the same bus and
124  * doesn't like to be waiting. Making transactions more frequent but shorter
125  * is a win.
126  */
127  n = MIN(n, 100);
128 
129  if (!_dev->get_semaphore()->take_nonblocking()) {
130  return 0;
131  }
132 
133  _dev->transfer_fullduplex(ff_stub, buf, n);
134  _dev->get_semaphore()->give();
135 
136  return n;
137 }
138 
140 {
141  if (_external) {
143  return;
144  }
145 
146  /* lower the update rate */
147  if (AP_HAL::micros() - _last_update_timestamp < 10000) {
148  return;
149  }
150 
152 
154 }
void begin(uint32_t b, uint16_t rxS, uint16_t txS)
void begin(uint32_t b)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev
Definition: SPIUARTDriver.h:19
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define debug(fmt, args ...)
uint32_t _last_update_timestamp
Definition: SPIUARTDriver.h:23
ByteBuffer _writebuf
Definition: UARTDriver.h:96
#define MIN(a, b)
Definition: usb_conf.h:215
const char * device_path
Definition: UARTDriver.h:90
int _read_fd(uint8_t *buf, uint16_t n)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual bool take_nonblocking() WARN_IF_UNUSED=0
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
virtual Semaphore * get_semaphore() override=0
virtual void _timer_tick(void) override
bool set_size(uint32_t size)
Definition: RingBuffer.cpp:20
virtual bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)=0
volatile bool _initialised
Definition: UARTDriver.h:91
virtual bool give()=0
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
virtual int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:324
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
virtual int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:343
int _write_fd(const uint8_t *buf, uint16_t n)
virtual bool set_speed(Device::Speed speed) override=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t micros()
Definition: system.cpp:152
ByteBuffer _readbuf
Definition: UARTDriver.h:95