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 <AP_HAL/AP_HAL.h>
18 #include <AP_HAL/utility/OwnPtr.h>
19 #include "Util.h"
20 #include "Scheduler.h"
21 #include "Semaphores.h"
22 #include <stdio.h>
23 
24 #if HAL_USE_SPI == TRUE
25 
26 using namespace ChibiOS;
27 extern const AP_HAL::HAL& hal;
28 
29 // SPI mode numbers
30 #define SPIDEV_MODE0 0
31 #define SPIDEV_MODE1 SPI_CR1_CPHA
32 #define SPIDEV_MODE2 SPI_CR1_CPOL
33 #define SPIDEV_MODE3 SPI_CR1_CPOL | SPI_CR1_CPHA
34 
35 #define SPI1_CLOCK STM32_PCLK2
36 #define SPI2_CLOCK STM32_PCLK1
37 #define SPI3_CLOCK STM32_PCLK1
38 #define SPI4_CLOCK STM32_PCLK2
39 
40 // expected bus clock speeds
41 static const uint32_t bus_clocks[4] = {
43 };
44 
45 static const struct SPIDriverInfo {
46  SPIDriver *driver;
47  uint8_t busid; // used for device IDs in parameters
48  uint8_t dma_channel_rx;
49  uint8_t dma_channel_tx;
50 } spi_devices[] = { HAL_SPI_BUS_LIST };
51 
52 #define MHZ (1000U*1000U)
53 #define KHZ (1000U)
54 // device list comes from hwdef.dat
55 ChibiOS::SPIDesc SPIDeviceManager::device_table[] = { HAL_SPI_DEVICE_LIST };
56 
57 SPIBus::SPIBus(uint8_t _bus) :
59  bus(_bus)
60 {
61  // allow for sharing of DMA channels with other peripherals
62  dma_handle = new Shared_DMA(spi_devices[bus].dma_channel_rx,
63  spi_devices[bus].dma_channel_tx,
66 
67 }
68 
69 /*
70  allocate DMA channel
71  */
73 {
74  // nothing to do as we call spiStart() on each transaction
75 }
76 
77 /*
78  deallocate DMA channel
79  */
81 {
82  // another non-SPI peripheral wants one of our DMA channels
83  if (spi_started) {
84  spiStop(spi_devices[bus].driver);
85  spi_started = false;
86  }
87 }
88 
89 
90 SPIDevice::SPIDevice(SPIBus &_bus, SPIDesc &_device_desc)
91  : bus(_bus)
92  , device_desc(_device_desc)
93 {
95  set_device_address(_device_desc.device);
98 
100 
101  asprintf(&pname, "SPI:%s:%u:%u",
103  (unsigned)bus.bus, (unsigned)device_desc.device);
104  //printf("SPI device %s on %u:%u at speed %u mode %u\n",
105  // device_desc.name,
106  // (unsigned)bus.bus, (unsigned)device_desc.device,
107  // (unsigned)frequency, (unsigned)device_desc.mode);
108 }
109 
111 {
112  //printf("SPI device %s on %u:%u closed\n", device_desc.name,
113  // (unsigned)bus.bus, (unsigned)device_desc.device);
114  free(pname);
115 }
116 
117 SPIDriver * SPIDevice::get_driver() {
119 }
120 
122 {
123  switch (speed) {
126  break;
129  break;
130  }
131  return true;
132 }
133 
134 /*
135  low level transfer function
136  */
137 void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
138 {
139  bool old_cs_forced = cs_forced;
140 
141  if (!set_chip_select(true)) {
142  return;
143  }
144  uint8_t *recv_buf = recv;
145  const uint8_t *send_buf = send;
146 
147  bus.bouncebuffer_setup(send_buf, len, recv_buf, len);
148 
149  if (send == nullptr) {
150  spiReceive(spi_devices[device_desc.bus].driver, len, recv_buf);
151  } else if (recv == nullptr) {
152  spiSend(spi_devices[device_desc.bus].driver, len, send_buf);
153  } else {
154  spiExchange(spi_devices[device_desc.bus].driver, len, send_buf, recv_buf);
155  }
156 
157  if (recv_buf != recv) {
158  memcpy(recv, recv_buf, len);
159  }
160 
161  set_chip_select(old_cs_forced);
162 }
163 
164 bool SPIDevice::clock_pulse(uint32_t n)
165 {
166  if (!cs_forced) {
167  //special mode to init sdcard without cs asserted
169  acquire_bus(true, true);
170  spiIgnore(spi_devices[device_desc.bus].driver, n);
171  acquire_bus(false, true);
172  bus.semaphore.give();
173  } else {
175  spiIgnore(spi_devices[device_desc.bus].driver, n);
176  }
177  return true;
178 }
179 
180 uint16_t SPIDevice::derive_freq_flag(uint32_t _frequency)
181 {
182  uint32_t spi_clock_freq = SPI1_CLOCK;
183  uint8_t busid = spi_devices[device_desc.bus].busid;
184  if (busid > 0 && busid-1 < ARRAY_SIZE_SIMPLE(bus_clocks)) {
185  spi_clock_freq = bus_clocks[busid-1] / 2;
186  }
187 
188  // find first divisor that brings us below the desired SPI clock
189  uint32_t i = 0;
190  while (spi_clock_freq > _frequency && i<7) {
191  spi_clock_freq >>= 1;
192  i++;
193  }
194 
195  // assuming the bitrate bits are consecutive in the CR1 register,
196  // we can just multiply by BR_0 to get the right bits for the desired
197  // scaling
198  return i * SPI_CR1_BR_0;
199 }
200 
201 bool SPIDevice::transfer(const uint8_t *send, uint32_t send_len,
202  uint8_t *recv, uint32_t recv_len)
203 {
204  if (!bus.semaphore.check_owner()) {
205  hal.console->printf("SPI: not owner of 0x%x\n", unsigned(get_bus_id()));
206  return false;
207  }
208  if ((send_len == recv_len && send == recv) || !send || !recv) {
209  // simplest cases, needed for DMA
210  do_transfer(send, recv, recv_len?recv_len:send_len);
211  return true;
212  }
213  uint8_t buf[send_len+recv_len];
214  if (send_len > 0) {
215  memcpy(buf, send, send_len);
216  }
217  if (recv_len > 0) {
218  memset(&buf[send_len], 0, recv_len);
219  }
220  do_transfer(buf, buf, send_len+recv_len);
221  if (recv_len > 0) {
222  memcpy(recv, &buf[send_len], recv_len);
223  }
224  return true;
225 }
226 
227 bool SPIDevice::transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len)
228 {
230  uint8_t buf[len];
231  memcpy(buf, send, len);
232  do_transfer(buf, buf, len);
233  memcpy(recv, buf, len);
234  return true;
235 }
236 
238 {
239  return &bus.semaphore;
240 }
241 
242 
243 AP_HAL::Device::PeriodicHandle SPIDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
244 {
245  return bus.register_periodic_callback(period_usec, cb, this);
246 }
247 
249 {
250  return bus.adjust_timer(h, period_usec);
251 }
252 
253 /*
254  used to acquire bus and (optionally) assert cs
255 */
256 bool SPIDevice::acquire_bus(bool set, bool skip_cs)
257 {
259  if (set && cs_forced) {
260  return true;
261  }
262  if (!set && !cs_forced) {
263  return false;
264  }
265  if (!set && cs_forced) {
266  if(!skip_cs) {
267  spiUnselectI(spi_devices[device_desc.bus].driver); /* Slave Select de-assertion. */
268  }
269  spiReleaseBus(spi_devices[device_desc.bus].driver); /* Ownership release. */
270  cs_forced = false;
271  bus.dma_handle->unlock();
272  } else {
273  bus.dma_handle->lock();
274  spiAcquireBus(spi_devices[device_desc.bus].driver); /* Acquire ownership of the bus. */
275  bus.spicfg.end_cb = nullptr;
276  bus.spicfg.ssport = PAL_PORT(device_desc.pal_line);
277  bus.spicfg.sspad = PAL_PAD(device_desc.pal_line);
278  bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode);
279  bus.spicfg.cr2 = 0;
280  if (bus.spi_started) {
281  spiStop(spi_devices[device_desc.bus].driver);
282  bus.spi_started = false;
283  }
284  spiStart(spi_devices[device_desc.bus].driver, &bus.spicfg); /* Setup transfer parameters. */
285  bus.spi_started = true;
286  if(!skip_cs) {
287  spiSelectI(spi_devices[device_desc.bus].driver); /* Slave Select assertion. */
288  }
289  cs_forced = true;
290  }
291  return true;
292 }
293 
294 /*
295  allow for control of SPI chip select pin
296  */
298  return acquire_bus(set, false);
299 }
300 
301 /*
302  return a SPIDevice given a string device name
303  */
306 {
307  /* Find the bus description in the table */
308  uint8_t i;
309  for (i = 0; i<ARRAY_SIZE_SIMPLE(device_table); i++) {
310  if (strcmp(device_table[i].name, name) == 0) {
311  break;
312  }
313  }
314  if (i == ARRAY_SIZE_SIMPLE(device_table)) {
315  printf("SPI: Invalid device name: %s\n", name);
316  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(nullptr);
317  }
318 
319  SPIDesc &desc = device_table[i];
320 
321  // find the bus
322  SPIBus *busp;
323  for (busp = buses; busp; busp = (SPIBus *)busp->next) {
324  if (busp->bus == desc.bus) {
325  break;
326  }
327  }
328  if (busp == nullptr) {
329  // create a new one
330  busp = new SPIBus(desc.bus);
331  if (busp == nullptr) {
332  return nullptr;
333  }
334  busp->next = buses;
335  busp->bus = desc.bus;
336 
337  buses = busp;
338  }
339 
340  return AP_HAL::OwnPtr<AP_HAL::SPIDevice>(new SPIDevice(*busp, desc));
341 }
342 
343 #ifdef HAL_SPI_CHECK_CLOCK_FREQ
344 /*
345  test clock frequencies. This measures the actual SPI clock
346  frequencies on all configured SPI buses. Used during board bringup
347  to validate clock configuration
348  */
349 void SPIDevice::test_clock_freq(void)
350 {
351  // delay for USB to come up
352  hal.console->printf("Waiting for USB\n");
353  hal.scheduler->delay(1000);
354  hal.console->printf("SPI1_CLOCK=%u SPI2_CLOCK=%u SPI3_CLOCK=%u SPI4_CLOCK=%u\n",
356 
357  // we will send 1024 bytes without any CS asserted and measure the
358  // time it takes to do the transfer
359  uint16_t len = 1024;
360  uint8_t *buf = (uint8_t *)hal.util->malloc_type(len, AP_HAL::Util::MEM_DMA_SAFE);
361  for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(spi_devices); i++) {
362  SPIConfig spicfg {};
363  // use a clock divisor of 256 for maximum resolution
364  spicfg.cr1 = SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0; // clock / 256
365  spiAcquireBus(spi_devices[i].driver);
366  spiStart(spi_devices[i].driver, &spicfg);
367  uint32_t t0 = AP_HAL::micros();
368  spiExchange(spi_devices[i].driver, len, buf, buf);
369  uint32_t t1 = AP_HAL::micros();
370  spiStop(spi_devices[i].driver);
371  spiReleaseBus(spi_devices[i].driver);
372  hal.console->printf("SPI[%u] clock=%u\n", spi_devices[i].busid, unsigned(256ULL * 1000000ULL * len * 8ULL / uint64_t(t1 - t0)));
373  }
374  hal.util->free_type(buf, len, AP_HAL::Util::MEM_DMA_SAFE);
375 }
376 #endif // HAL_SPI_CHECK_CLOCK_FREQ
377 
378 #endif // HAL_USE_SPI
int printf(const char *fmt,...)
Definition: stdio.c:113
#define APM_SPI_PRIORITY
Definition: Scheduler.h:44
bool clock_pulse(uint32_t len) override
Definition: SPIDevice.cpp:164
void dma_deallocate(Shared_DMA *ctx)
Definition: SPIDevice.cpp:80
uint16_t mode
Definition: SPIDevice.h:53
uint8_t device
Definition: SPIDevice.h:51
bool spi_started
Definition: SPIDevice.h:36
uint8_t bus
Definition: SPIDevice.h:32
AP_HAL::UARTDriver * console
Definition: HAL.h:110
uint32_t get_bus_id(void) const
Definition: Device.h:60
void set_device_bus(uint8_t bus)
Definition: Device.h:291
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len, uint8_t *&buf_rx, uint16_t rx_len)
Definition: Device.cpp:150
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:201
SPIBus(uint8_t bus)
Definition: SPIDevice.cpp:57
AP_HAL::Util * util
Definition: HAL.h:115
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
static SPIDesc device_table[]
Definition: SPIDevice.h:131
const char * name
Definition: BusTest.cpp:11
bool acquire_bus(bool acquire, bool skip_cs)
Definition: SPIDevice.cpp:256
virtual void free_type(void *ptr, size_t size, Memory_Type mem_type)
Definition: Util.h:116
SPIDesc & device_desc
Definition: SPIDevice.h:108
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual ~SPIDevice()
Definition: SPIDevice.cpp:110
t0
Definition: calcTms.c:1
uint16_t freq_flag
Definition: SPIDevice.h:110
virtual void delay(uint16_t ms)=0
Shared_DMA * dma_handle
Definition: Device.h:32
uint8_t dma_channel_tx
Definition: SPIDevice.cpp:49
uint8_t dma_channel_rx
Definition: SPIDevice.cpp:48
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
SPIDriver * driver
Definition: SPIDevice.cpp:46
void assert_owner(void)
Definition: Semaphores.h:41
uint16_t freq_flag_low
Definition: SPIDevice.h:111
#define SPI2_CLOCK
Definition: SPIDevice.cpp:36
void dma_allocate(Shared_DMA *ctx)
Definition: SPIDevice.cpp:72
Semaphore semaphore
Definition: Device.h:31
void * PeriodicHandle
Definition: Device.h:42
const char * name
Definition: SPIDevice.h:49
uint16_t freq_flag_high
Definition: SPIDevice.h:112
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:32
ioline_t pal_line
Definition: SPIDevice.h:52
static const uint32_t bus_clocks[4]
Definition: SPIDevice.cpp:41
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:121
static const struct SPIDriverInfo spi_devices[]
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
Definition: SPIDevice.cpp:227
void free(void *ptr)
Definition: malloc.c:81
virtual void * malloc_type(size_t size, Memory_Type mem_type)
Definition: Util.h:115
SPIConfig spicfg
Definition: SPIDevice.h:33
struct DeviceBus * next
Definition: Device.h:30
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: SPIDevice.cpp:243
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:84
bool check_owner(void)
Definition: Semaphores.h:34
uint16_t derive_freq_flag(uint32_t _frequency)
Definition: SPIDevice.cpp:180
uint32_t highspeed
Definition: SPIDevice.h:55
#define ARRAY_SIZE_SIMPLE(_arr)
Definition: AP_Common.h:83
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:133
AP_HAL::OwnPtr< AP_HAL::SPIDevice > get_device(const char *name)
Definition: SPIDevice.cpp:305
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define SPI1_CLOCK
Definition: SPIDevice.cpp:35
void do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
Definition: SPIDevice.cpp:137
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: SPIDevice.cpp:248
void set_device_address(uint8_t address)
Definition: Device.h:286
#define SPI3_CLOCK
Definition: SPIDevice.cpp:37
AP_HAL::Semaphore * get_semaphore() override
Definition: SPIDevice.cpp:237
uint32_t lowspeed
Definition: SPIDevice.h:54
uint32_t micros()
Definition: system.cpp:152
uint8_t busid
Definition: SPIDevice.cpp:47
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool set_chip_select(bool set) override
Definition: SPIDevice.cpp:297
SPIDriver * get_driver()
Definition: SPIDevice.cpp:117
#define SPI4_CLOCK
Definition: SPIDevice.cpp:38