APM:Libraries
SPIDevice.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "SPIDevice.h"
16 
17 #include <arch/board/board.h>
18 #include "board_config.h"
19 #include <drivers/device/spi.h>
20 #include <stdio.h>
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_HAL/utility/OwnPtr.h>
23 #include "Scheduler.h"
24 #include "Semaphores.h"
25 
26 /*
27  NuttX on STM32 doesn't produce the exact SPI bus frequency
28  requested. This is a table mapping requested to achieved SPI
29  frequency for a 168 MHz processor :
30 
31  2 -> 1.3 MHz
32  4 -> 2.6 MHz
33  6 -> 5.3 MHz
34  8 -> 5.3 MHz
35  10 -> 5.3 MHz
36  11 -> 10
37  12 -> 10
38  13 -> 10
39  14 -> 10
40  16 -> 10
41  18 -> 10
42  20 -> 10
43  21 -> 20
44  28 -> 20
45 
46 For a 180 MHz processor :
47 
48  2 -> 1.4 MHz
49  4 -> 2.8 MHz
50  6 -> 5.6 MHz
51  8 -> 5.6 MHz
52  10 -> 5.6 MHz
53  11 -> 5.6 MHz
54  12 -> 11.25 MHz
55  13 -> 11.25 MHz
56  14 -> 11.25 MHz
57  16 -> 11.25 MHz
58  18 -> 11.25 MHz
59  20 -> 11.25 MHz
60  22 -> 11.25 MHz
61  24 -> 22.5 MHz
62  28 -> 22.5 MHz
63 
64  */
65 
66 namespace VRBRAIN {
67 
68 #define MHZ (1000U*1000U)
69 #define KHZ (1000U)
70 
72 
73 #if defined(SPIDEV_MS5611)
74  SPIDesc("ms5611", PX4_SPI_BUS_1, (spi_dev_e)SPIDEV_MS5611, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
75 #endif
76 #if defined(SPIDEV_EXP_MS5611)
77  SPIDesc("ms5611_ext", PX4_SPI_BUS_1, (spi_dev_e)SPIDEV_EXP_MS5611, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
78 #endif
79 #if defined(SPIDEV_EXP_MPU6000)
80  SPIDesc("mpu6000_ext", PX4_SPI_BUS_1, (spi_dev_e)SPIDEV_EXP_MPU6000, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
81 #endif
82 #if defined(SPIDEV_EXP_HMC5983)
83  SPIDesc("hmc5983_ext", PX4_SPI_BUS_1, (spi_dev_e)SPIDEV_EXP_HMC5983, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
84 #endif
85 #if defined(SPIDEV_MPU6000)
86  SPIDesc("mpu6000", PX4_SPI_BUS_2, (spi_dev_e)SPIDEV_MPU6000, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
87 #endif
88 #if defined(SPIDEV_IMU_MS5611)
89  SPIDesc("ms5611_imu", PX4_SPI_BUS_2, (spi_dev_e)SPIDEV_IMU_MS5611, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
90 #endif
91 #if defined(SPIDEV_IMU_MPU6000)
92  SPIDesc("mpu6000_imu", PX4_SPI_BUS_2, (spi_dev_e)SPIDEV_IMU_MPU6000, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
93 #endif
94 #if defined(SPIDEV_IMU_HMC5983)
95  SPIDesc("hmc5983_imu", PX4_SPI_BUS_2, (spi_dev_e)SPIDEV_IMU_HMC5983, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
96 #endif
97 #if defined(SPIDEV_MPU9250)
98  SPIDesc("mpu9250", PX4_SPI_BUS_2, (spi_dev_e)SPIDEV_MPU9250, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
99 #endif
100 
101 
102 
103 
104 
105 
106 
107 
108 
109 
110 
111 
112 
113 
114 
115 
116 
117 
118 
119 
120 
121 
122 
123 
124 
125 
126 
127 
128 
129 
130 
131 
132 
133 
134 
135 
136 
137 
138 
139 
140 
141 
142 
143 
144 
145 
146  SPIDesc(nullptr, 0, (spi_dev_e)0, (spi_mode_e)0, 0, 0),
147 };
148 
149 SPIDevice::SPIDevice(SPIBus &_bus, SPIDesc &_device_desc)
150  : bus(_bus)
151  , device_desc(_device_desc)
152 {
153  set_device_bus(_bus.bus);
154  set_device_address(_device_desc.device);
156  SPI_SELECT(bus.dev, device_desc.device, false);
157  asprintf(&pname, "SPI:%s:%u:%u",
159  (unsigned)bus.bus, (unsigned)device_desc.device);
160  perf = perf_alloc(PC_ELAPSED, pname);
161  printf("SPI device %s on %u:%u at speed %u mode %u\n",
163  (unsigned)bus.bus, (unsigned)device_desc.device,
164  (unsigned)frequency, (unsigned)device_desc.mode);
165 }
166 
168 {
169  printf("SPI device %s on %u:%u closed\n", device_desc.name,
170  (unsigned)bus.bus, (unsigned)device_desc.device);
171  perf_free(perf);
172  free(pname);
173 }
174 
176 {
177  switch (speed) {
180  break;
183  break;
184  }
185  return true;
186 }
187 
188 /*
189  low level transfer function
190  */
191 void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
192 {
193  /*
194  to accomodate the method in PX4 drivers of using interrupt
195  context for SPI device transfers we need to check if PX4 has
196  registered a driver on this bus. If not then we can avoid the
197  irqsave/irqrestore and get bus parallelism for DMA enabled
198  buses.
199 
200  There is a race in this if a PX4 driver starts while we are
201  running this, but that would only happen at early boot and is
202  very unlikely
203 
204  yes, this is a nasty hack. Suggestions for a better method
205  appreciated.
206  */
207  bool use_irq_save = up_spi_use_irq_save(bus.dev);
208  irqstate_t state;
209  if (use_irq_save) {
210  state = irqsave();
211  }
212  perf_begin(perf);
213  SPI_LOCK(bus.dev, true);
214  SPI_SETFREQUENCY(bus.dev, frequency);
215  SPI_SETMODE(bus.dev, device_desc.mode);
216  SPI_SETBITS(bus.dev, 8);
217  SPI_SELECT(bus.dev, device_desc.device, true);
218  SPI_EXCHANGE(bus.dev, send, recv, len);
219  if (!cs_forced) {
220  SPI_SELECT(bus.dev, device_desc.device, false);
221  }
222  SPI_LOCK(bus.dev, false);
223  perf_end(perf);
224  if (use_irq_save) {
225  irqrestore(state);
226  }
227 }
228 
229 bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
230  uint8_t *recv, uint32_t recv_len)
231 {
232  if (send_len == recv_len && send == recv) {
233  // simplest cases, needed for DMA
234  do_transfer(send, recv, recv_len);
235  return true;
236  }
237  uint8_t buf[send_len+recv_len];
238  if (send_len > 0) {
239  memcpy(buf, send, send_len);
240  }
241  if (recv_len > 0) {
242  memset(&buf[send_len], 0, recv_len);
243  }
244  do_transfer(buf, buf, send_len+recv_len);
245  if (recv_len > 0) {
246  memcpy(recv, &buf[send_len], recv_len);
247  }
248  return true;
249 }
250 
251 bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)
252 {
253  uint8_t buf[len];
254  memcpy(buf, send, len);
255  do_transfer(buf, buf, len);
256  memcpy(recv, buf, len);
257  return true;
258 }
259 
261 {
262  return &bus.semaphore;
263 }
264 
265 
266 AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
267 {
268  return bus.register_periodic_callback(period_usec, cb, this);
269 }
270 
272 {
273  return bus.adjust_timer(h, period_usec);
274 }
275 
276 /*
277  allow for control of SPI chip select pin
278  */
280 {
281  cs_forced = set;
282  SPI_SELECT(bus.dev, device_desc.device, set);
283  return true;
284 }
285 
286 
287 /*
288  return a SPIDevice given a string device name
289  */
292 {
293  /* Find the bus description in the table */
294  uint8_t i;
295  for (i = 0; device_table[i].name; i++) {
296  if (strcmp(device_table[i].name, name) == 0) {
297  break;
298  }
299  }
300  if (device_table[i].name == nullptr) {
301  printf("SPI: Invalid device name: %s\n", name);
302  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
303  }
304 
305  SPIDesc &desc = device_table[i];
306 
307  // find the bus
308  SPIBus *busp;
309  for (busp = buses; busp; busp = (SPIBus *)busp->next) {
310  if (busp->bus == desc.bus) {
311  break;
312  }
313  }
314  if (busp == nullptr) {
315  // create a new one
316  busp = new SPIBus;
317  if (busp == nullptr) {
318  return nullptr;
319  }
320  busp->next = buses;
321  busp->bus = desc.bus;
322  busp->dev = up_spiinitialize(desc.bus);
323  buses = busp;
324  }
325 
326  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(*busp, desc));
327 }
328 
329 }
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
Definition: SPIDevice.cpp:251
int printf(const char *fmt,...)
Definition: stdio.c:113
struct F4Light::SPIDESC SPIDesc
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: SPIDevice.cpp:271
struct spi_dev_s * dev
Definition: SPIDevice.h:33
void set_device_bus(uint8_t bus)
Definition: Device.h:291
AP_HAL::Semaphore * get_semaphore() override
Definition: SPIDevice.cpp:260
SPIDesc & device_desc
Definition: SPIDevice.h:89
const char * name
Definition: BusTest.cpp:11
void do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
Definition: SPIDevice.cpp:191
struct DeviceBus * next
Definition: Device.h:29
#define SPIDEV_MODE3
Definition: SPIDevice.cpp:33
uint32_t lowspeed
Definition: SPIDevice.h:50
virtual ~SPIDevice()
Definition: SPIDevice.cpp:167
#define MHZ
Definition: SPIDevice.cpp:68
perf_counter_t perf
Definition: SPIDevice.h:91
void * PeriodicHandle
Definition: Device.h:42
enum spi_dev_e device
Definition: SPIDevice.h:48
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:229
enum spi_mode_e mode
Definition: SPIDevice.h:49
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:102
static int state
Definition: Util.cpp:20
uint32_t highspeed
Definition: SPIDevice.h:51
const char * name
Definition: SPIDevice.h:46
Semaphore semaphore
Definition: Device.h:30
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:175
void free(void *ptr)
Definition: malloc.c:81
uint32_t frequency
Definition: SPIDevice.h:90
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
Definition: SPIDevice.cpp:291
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: SPIDevice.cpp:266
bool set_chip_select(bool set) override
Definition: SPIDevice.cpp:279
#define KHZ
Definition: SPIDevice.cpp:69
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
uint8_t bus
Definition: SPIDevice.h:34
void set_device_address(uint8_t address)
Definition: Device.h:286
static SPIDesc device_table[]
Definition: SPIDevice.h:109
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:140