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 PX4 {
67 
68 #define MHZ (1000U*1000U)
69 #define KHZ (1000U)
70 
72 #if defined(PX4_SPIDEV_MPU)
73  SPIDesc("mpu6000", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
74 #endif
75 #if defined(PX4_SPIDEV_EXT_BARO)
76  SPIDesc("ms5611_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
77 #endif
78 #if defined(PX4_SPIDEV_ICM)
79  SPIDesc("icm20608", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ICM, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
80 #endif
81 #if defined(PX4_SPIDEV_ACCEL_MAG)
82  // ICM20608 on the ACCEL_MAG
83  SPIDesc("icm20608-am", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
84 #endif
85 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V4
86  SPIDesc("ms5611_int", PX4_SPI_BUS_BARO, (spi_dev_e)PX4_SPIDEV_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
87 #ifdef PX4_SPIDEV_HMC
88  // r15 has LIS3MDL in place of HMC
89  SPIDesc("lis3mdl", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_HMC, SPIDEV_MODE3, 500*KHZ, 500*KHZ),
90 #endif
91 #endif
92 #ifdef PX4_SPIDEV_BARO
93  SPIDesc("ms5611", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, SPIDEV_MODE3, 20*MHZ, 20*MHZ),
94 #endif
95 #if defined(PX4_SPIDEV_ACCEL_MAG)
96  SPIDesc("lsm9ds0_am", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
97 #endif
98 #ifdef PX4_SPIDEV_EXT_ACCEL_MAG
99  SPIDesc("lsm9ds0_ext_am", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
100 #endif
101 #if defined(PX4_SPIDEV_GYRO)
102  SPIDesc("lsm9ds0_g", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
103 #endif
104 #ifdef PX4_SPIDEV_EXT_GYRO
105  SPIDesc("lsm9ds0_ext_g",PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
106 #endif
107 #if defined(PX4_SPIDEV_MPU)
108  SPIDesc("mpu9250", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
109  SPIDesc("mpu6500", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
110 #endif
111 #ifdef PX4_SPIDEV_EXT_MPU
112  SPIDesc("mpu6000_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 500*KHZ, 8*MHZ),
113  SPIDesc("mpu9250_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
114  SPIDesc("icm20608_ext", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU, SPIDEV_MODE3, 1*MHZ, 8*MHZ),
115 #endif
116 #ifdef PX4_SPIDEV_HMC
117  SPIDesc("hmc5843", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_HMC, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
118 #endif
119 #ifdef PX4_SPIDEV_LIS
120  SPIDesc("lis3mdl", PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_LIS, SPIDEV_MODE3, 500*KHZ, 500*KHZ),
121 #endif
122 
123 #ifdef PX4_SPI_BUS_EXT
124 #ifdef PX4_SPIDEV_EXT0
125  SPIDesc("external0m0", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT0, SPIDEV_MODE0, 2*MHZ, 2*MHZ),
126  SPIDesc("external0m1", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT0, SPIDEV_MODE1, 2*MHZ, 2*MHZ),
127  SPIDesc("external0m2", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT0, SPIDEV_MODE2, 2*MHZ, 2*MHZ),
128  SPIDesc("external0m3", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT0, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
129 #endif
130 #ifdef PX4_SPIDEV_EXT1
131  SPIDesc("external1", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT1, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
132 #endif
133 #ifdef PX4_SPIDEV_EXT2
134  SPIDesc("external2", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT2, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
135 #endif
136 #ifdef PX4_SPIDEV_EXT3
137  SPIDesc("external3", PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT3, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
138 #endif
139 #endif
140 
141 #ifdef CYRF_SPI_PX4_SPI_BUS
142  SPIDesc("cypress", CYRF_SPI_PX4_SPI_BUS, CYRF_SPI_PX4_SPIDEV_EXT, SPIDEV_MODE0, 2*MHZ, 2*MHZ),
143 #endif
144 
145  SPIDesc(nullptr, 0, (spi_dev_e)0, (spi_mode_e)0, 0, 0),
146 };
147 
148 SPIDevice::SPIDevice(SPIBus &_bus, SPIDesc &_device_desc)
149  : bus(_bus)
150  , device_desc(_device_desc)
151 {
152  set_device_bus(_bus.bus);
153  set_device_address(_device_desc.device);
155  SPI_SELECT(bus.dev, device_desc.device, false);
156  asprintf(&pname, "SPI:%s:%u:%u",
158  (unsigned)bus.bus, (unsigned)device_desc.device);
159  perf = perf_alloc(PC_ELAPSED, pname);
160  printf("SPI device %s on %u:%u at speed %u mode %u\n",
162  (unsigned)bus.bus, (unsigned)device_desc.device,
163  (unsigned)frequency, (unsigned)device_desc.mode);
164 }
165 
167 {
168  printf("SPI device %s on %u:%u closed\n", device_desc.name,
169  (unsigned)bus.bus, (unsigned)device_desc.device);
170  perf_free(perf);
171  free(pname);
172 }
173 
175 {
176  switch (speed) {
179  break;
182  break;
183  }
184  return true;
185 }
186 
187 /*
188  low level transfer function
189  */
190 void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
191 {
192  /*
193  to accomodate the method in PX4 drivers of using interrupt
194  context for SPI device transfers we need to check if PX4 has
195  registered a driver on this bus. If not then we can avoid the
196  irqsave/irqrestore and get bus parallelism for DMA enabled
197  buses.
198 
199  There is a race in this if a PX4 driver starts while we are
200  running this, but that would only happen at early boot and is
201  very unlikely
202 
203  yes, this is a nasty hack. Suggestions for a better method
204  appreciated.
205  */
206  bool use_irq_save = up_spi_use_irq_save(bus.dev);
207  irqstate_t state;
208  if (use_irq_save) {
209  state = irqsave();
210  }
211  perf_begin(perf);
212  SPI_LOCK(bus.dev, true);
213  SPI_SETFREQUENCY(bus.dev, frequency);
214  SPI_SETMODE(bus.dev, device_desc.mode);
215  SPI_SETBITS(bus.dev, 8);
216  SPI_SELECT(bus.dev, device_desc.device, true);
217  SPI_EXCHANGE(bus.dev, send, recv, len);
218  if (!cs_forced) {
219  SPI_SELECT(bus.dev, device_desc.device, false);
220  }
221  SPI_LOCK(bus.dev, false);
222  perf_end(perf);
223  if (use_irq_save) {
224  irqrestore(state);
225  }
226 }
227 
228 bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
229  uint8_t *recv, uint32_t recv_len)
230 {
231  if (send_len == recv_len && send == recv) {
232  // simplest cases, needed for DMA
233  do_transfer(send, recv, recv_len);
234  return true;
235  }
236  uint8_t buf[send_len+recv_len];
237  if (send_len > 0) {
238  memcpy(buf, send, send_len);
239  }
240  if (recv_len > 0) {
241  memset(&buf[send_len], 0, recv_len);
242  }
243  do_transfer(buf, buf, send_len+recv_len);
244  if (recv_len > 0) {
245  memcpy(recv, &buf[send_len], recv_len);
246  }
247  return true;
248 }
249 
250 bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)
251 {
252  uint8_t buf[len];
253  memcpy(buf, send, len);
254  do_transfer(buf, buf, len);
255  memcpy(recv, buf, len);
256  return true;
257 }
258 
260 {
261  return &bus.semaphore;
262 }
263 
264 
265 AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
266 {
267  return bus.register_periodic_callback(period_usec, cb, this);
268 }
269 
271 {
272  return bus.adjust_timer(h, period_usec);
273 }
274 
275 /*
276  allow for control of SPI chip select pin
277  */
279 {
280  cs_forced = set;
281  SPI_SELECT(bus.dev, device_desc.device, set);
282  return true;
283 }
284 
285 
286 /*
287  return a SPIDevice given a string device name
288  */
291 {
292  /* Find the bus description in the table */
293  uint8_t i;
294  for (i = 0; device_table[i].name; i++) {
295  if (strcmp(device_table[i].name, name) == 0) {
296  break;
297  }
298  }
299  if (device_table[i].name == nullptr) {
300  printf("SPI: Invalid device name: %s\n", name);
301  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
302  }
303 
304  SPIDesc &desc = device_table[i];
305 
306  // find the bus
307  SPIBus *busp;
308  for (busp = buses; busp; busp = (SPIBus *)busp->next) {
309  if (busp->bus == desc.bus) {
310  break;
311  }
312  }
313  if (busp == nullptr) {
314  // create a new one
315  busp = new SPIBus;
316  if (busp == nullptr) {
317  return nullptr;
318  }
319  busp->next = buses;
320  busp->bus = desc.bus;
321  busp->dev = up_spiinitialize(desc.bus);
322  buses = busp;
323  }
324 
325  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(*busp, desc));
326 }
327 
328 }
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: SPIDevice.cpp:265
int printf(const char *fmt,...)
Definition: stdio.c:113
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
Definition: SPIDevice.cpp:250
SPIDesc & device_desc
Definition: SPIDevice.h:89
struct F4Light::SPIDESC SPIDesc
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:140
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: SPIDevice.cpp:270
char * pname
Definition: SPIDevice.h:92
void set_device_bus(uint8_t bus)
Definition: Device.h:291
#define SPIDEV_MODE2
Definition: SPIDevice.cpp:32
const char * name
Definition: BusTest.cpp:11
uint8_t bus
Definition: SPIDevice.h:34
AP_HAL::Semaphore * get_semaphore() override
Definition: SPIDevice.cpp:259
bool cs_forced
Definition: SPIDevice.h:93
#define SPIDEV_MODE3
Definition: SPIDevice.cpp:33
uint32_t highspeed
Definition: SPIDevice.h:51
#define SPIDEV_MODE1
Definition: SPIDevice.cpp:31
SPIBus & bus
Definition: SPIDevice.h:88
#define KHZ
Definition: SPIDevice.cpp:69
enum spi_dev_e device
Definition: SPIDevice.h:48
uint32_t frequency
Definition: SPIDevice.h:90
bool set_chip_select(bool set) override
Definition: SPIDevice.cpp:278
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:102
void * PeriodicHandle
Definition: Device.h:42
perf_counter_t perf
Definition: SPIDevice.h:91
enum spi_mode_e mode
Definition: SPIDevice.h:49
static int state
Definition: Util.cpp:20
struct DeviceBus * next
Definition: Device.h:29
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
Definition: SPIDevice.cpp:290
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:228
void do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
Definition: SPIDevice.cpp:190
static SPIDesc device_table[]
Definition: SPIDevice.h:109
struct spi_dev_s * dev
Definition: SPIDevice.h:33
void free(void *ptr)
Definition: malloc.c:81
#define SPIDEV_MODE0
Definition: SPIDevice.cpp:30
Semaphore semaphore
Definition: Device.h:30
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:174
uint32_t lowspeed
Definition: SPIDevice.h:50
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
const char * name
Definition: SPIDevice.h:46
void set_device_address(uint8_t address)
Definition: Device.h:286
#define MHZ
Definition: SPIDevice.cpp:68
virtual ~SPIDevice()
Definition: SPIDevice.cpp:166