APM:Libraries
SPIDevice.cpp
Go to the documentation of this file.
1 
3 /*
4 (c) 2017 night_ghost@ykoctpa.ru
5 
6 */
7 
8 
9 #pragma GCC optimize ("O2")
10 
11 #include <AP_HAL/AP_HAL.h>
12 
13 
14 #include <spi.h>
15 #include "Semaphores.h"
16 
17 #include <inttypes.h>
18 #include <vector>
19 #include <AP_HAL/HAL.h>
20 #include <AP_HAL/SPIDevice.h>
21 
22 #include "Scheduler.h"
23 #include <spi.h>
24 #include <boards.h>
25 
26 #include "SPIDevice.h"
27 #include "GPIO.h"
28 
29 
30 using namespace F4Light;
31 
32 
33 extern const SPIDesc spi_device_table[]; // different SPI tables per board subtype
34 
35 extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES;
36 
37 static const spi_pins board_spi_pins[] = {
38  { // 0
42  },
43  { // 1
47  },
48  { //2
52  }
53 };
54 
55 
58 uint8_t * SPIDevice::buffer[MAX_BUS_NUM] IN_CCM; // DMA buffers in RAM
59 
60 #ifdef DEBUG_SPI
61 spi_trans SPIDevice::spi_trans_array[SPI_LOG_SIZE] IN_CCM;
62 uint8_t SPIDevice::spi_trans_ptr=0;
63 #endif
64 
65 
66 #ifdef BOARD_SOFTWARE_SPI
67 
68 // as fast as possible
69 #define SCK_H {sck_port->BSRRL = sck_pin; }
70 #define SCK_L {sck_port->BSRRH = sck_pin; }
71 
72 #define MOSI_H {mosi_port->BSRRL = mosi_pin; }
73 #define MOSI_L {mosi_port->BSRRH = mosi_pin; }
74 
75 #define MISO_read ((miso_port->IDR & miso_pin)!=0)
76 
77 
78 static void dly_spi() {
79  delay_ns100(dly_time);
80 };
81 
82 
83 uint8_t SPIDevice::_transfer_s(uint8_t bt) {
84 
85  for(int ii = 0; ii < 8; ++ii) {
86  if (bt & 0x80) {
87  MOSI_H;
88  } else {
89  MOSI_L;
90  }
91  SCK_L;
92 
93  dly_spi();
94  SCK_H;
95 
96  bt <<= 1;
97  if (MISO_read) {
98  bt |= 1;
99  }
100  dly_spi();
101  }
102 
103  return bt;
104 }
105 
106 void SPIDevice::spi_soft_set_speed(){
107  uint16_t rate;
108 
109  switch(_speed) {
110  case SPI_36MHZ:
111  case SPI_18MHZ:
112  case SPI_9MHZ:
113  case SPI_4_5MHZ:
114  rate = 1;
115  break;
116  case SPI_2_25MHZ:
117  rate = 2;
118  break;
119  case SPI_1_125MHZ:
120  rate = 4; // 400 ns delay
121  break;
122  case SPI_562_500KHZ:
123  rate = 8;
124  break;
125  case SPI_281_250KHZ:
126  rate = 16;
127  break;
128  case SPI_140_625KHZ:
129  default:
130  rate = 32;
131  break;
132  }
133  dly_time = rate;
134 }
135 
136 #endif
137 
139  if(_completion_cb){ // IOC from last call still not called - timeout
140  // TODO: ???
141  }
142  _completion_cb = h;
143 }
144 
145 
146 uint8_t SPIDevice::transfer(uint8_t out){
147 #ifdef BOARD_SOFTWARE_SPI
148  if(_desc.mode == SPI_TRANSFER_SOFT) {
149  return _transfer_s(out);
150  } else
151 #endif
152  {
153  return _transfer(out);
154  }
155 
156 }
157 
158 
159 uint8_t SPIDevice::_transfer(uint8_t data) {
160  (void)_desc.dev->SPIx->DR; // read fake data out
161 
162  //wait for TXE before send
163  while (!spi_is_tx_empty(_desc.dev)) { // should wait transfer finished
164  if(!spi_is_busy(_desc.dev) ) break;
165  }
166 
167  //write 1byte
168  _desc.dev->SPIx->DR = data;
169 
170  //wait for read byte
171  while (!spi_is_rx_nonempty(_desc.dev)) { // should wait transfer finished
172  if(!spi_is_busy(_desc.dev) ) break;
173  }
174 
175  return (uint8_t)(_desc.dev->SPIx->DR); // we got a byte so transfer complete
176 }
177 
178 void SPIDevice::send(uint8_t out) {
179  //wait for TXE before send
180  while (!spi_is_tx_empty(_desc.dev)) { // should wait transfer finished
181  if(!spi_is_busy(_desc.dev) ) break;
182  }
183  //write 1byte
184  spi_tx_reg(_desc.dev, out); // _desc.dev->SPIx->DR = data;
185 }
186 
187 
188 bool SPIDevice::transfer(const uint8_t *out, uint32_t send_len, uint8_t *recv, uint32_t recv_len){
189 
190  uint8_t err=1;
191 
192 // differrent devices on bus requires different modes
193  if(owner[_desc.bus-1] != this) { // bus was in use by another driver so SPI hardware need reinit
194  _initialized=false;
195  }
196 
197  if(!_initialized){
198  init();
199  if(!_initialized) return false;
200  owner[_desc.bus-1] = this; // Got it!
201  }
202 
203 #ifdef BOARD_SOFTWARE_SPI
204 
205 // not deleted for case of needs for external SPI on arbitrary pins
206 
207  if(_desc.mode == SPI_TRANSFER_SOFT) {
208  spi_soft_set_speed();
209 
210  _cs_assert();
211 
212 
213  if (out != NULL && send_len) {
214  for (uint16_t i = 0; i < send_len; i++) {
215  _transfer_s(out[i]);
216  }
217  }
218 
219  if(recv !=NULL && recv_len) {
220  for (uint16_t i = 0; i < recv_len; i++) {
221  recv[i] = _transfer_s(0xff);
222  }
223  }
224 
225  _cs_release();
226 
227  if(_completion_cb) {
229  _completion_cb=0;
230  }
231  } else
232 #endif
233  {
234 
235  uint32_t t = hal_micros();
236  while(_desc.dev->state->busy){ // wait for previous transfer finished
237  if(hal_micros() - t > 5000){
238  // TODO increment grab counter
239  break; // SPI transfer can't be so long so let grab the bus
240  }
241  hal_yield(0);
242  }
243 
244 
246 
247  _desc.dev->state->busy = true; // we got bus
248  _cs_assert();
249 
250  _send_address = out; // remember transfer params for ISR
251  _send_len = send_len;
252  _dummy_len = send_len;
253  _recv_address = recv;
254  _recv_len = recv_len;
255 
256 
257 #define MIN_DMA_BYTES 1 // 4 // write to 2-byte register not uses DMA, 4-byte command to DataFlash will
258 //#define MIN_DMA_BYTES 32 // for debug
259 
260  switch(_desc.mode){
261 
262  case SPI_TRANSFER_DMA: // DMA
263  if(send_len + recv_len >= MIN_DMA_BYTES) {
264  get_dma_ready();
265  uint8_t nb = _desc.bus-1;
266 
267  bool can_dma = false;
268  _desc.dev->state->len=0;
269 
270  // alloc buffer if recv needed - to not in ISR
271  if(recv_len && !ADDRESS_IN_RAM(recv)){ //not in CCM
272  if(buffer[nb] == NULL){
273  buffer[nb] = (uint8_t *)malloc(SPI_BUFFER_SIZE); // allocate only on 1st use
274  }
275  }
276 
278 
279  if(send_len){
280 
281 //[ for debug
282 // if(send_len>1){
283 //]
284  if(ADDRESS_IN_RAM(out)){ // not in CCM
285  can_dma=true;
286  } else {
287  if(send_len<=SPI_BUFFER_SIZE){
288  if(buffer[nb] == NULL){ // allocate only on 1st use
289  buffer[nb] = (uint8_t *)malloc(SPI_BUFFER_SIZE);
290  }
291  if(buffer[nb]){
292  memmove(buffer[nb],out,send_len);
293  out = buffer[nb];
294  _send_len=0;
295  can_dma=true;
296  }
297  }
298  }
299 //[ for debug
300 // }
301 //]
302 
303  if(can_dma){
304  setup_dma_transfer(out, NULL, send_len);
305  } else {
306  _isr_mode = SPI_ISR_SEND_DMA; // try DMA on receive
308  }
309  } else { // send_len == 0 so there will no RXNE interrupts so
310  // we need setup DMA RX transfer here
311  uint16_t len = _recv_len;
312  if(ADDRESS_IN_RAM(recv)){ //not in CCM
313  _desc.dev->state->len=0;
314  can_dma=true;
315  }else if(len<=SPI_BUFFER_SIZE && buffer[nb]){
316  _desc.dev->state->len=len;
317  _desc.dev->state->dst=recv;
318  recv = buffer[nb];
319  can_dma=true;
320  }
321  if(can_dma){
322  setup_dma_transfer(NULL, recv, len);
323  _recv_len=0;
324  } else {
325  _isr_mode = SPI_ISR_RECEIVE; // just receive
327  }
328  }
329 
330  err = do_transfer(can_dma, send_len + recv_len);
331  break;
332  }
333  // no break!
334 
335  case SPI_TRANSFER_INTR: // interrupts
338  err=do_transfer(false, send_len + recv_len);
339  break;
340 
341  case SPI_TRANSFER_POLL: // polling
342  err = spimaster_transfer(_desc.dev, out, send_len, recv, recv_len);
343  _cs_release();
344  _desc.dev->state->busy=false;
345  if(_completion_cb) {
347  _completion_cb=0;
348  }
349  break;
350 
351 
352  default:
353  break;
354  }
355  }
356 
357 
358 
359  return err==0;
360 
361 }
362 
363 
364 
365 
366 // not used anywhere
367 
368 bool SPIDevice::transfer_fullduplex(const uint8_t *out, uint8_t *recv, uint32_t len) {
369 
370 
371  if(owner[_desc.bus-1] != this) { // bus was in use by another driver so need reinit
372  _initialized=false;
373  }
374 
375  if(!_initialized) {
376  init();
377  if(!_initialized) return false;
378  owner[_desc.bus-1] = this; // Got it!
379  }
380 
381 
382 #ifdef BOARD_SOFTWARE_SPI
383  if(_desc.mode == SPI_TRANSFER_SOFT) {
384  _cs_assert();
385  spi_soft_set_speed();
386 
387  if (out != NULL && recv !=NULL && len) {
388  for (uint16_t i = 0; i < len; i++) {
389  recv[i] = _transfer_s(out[i]);
390  }
391  }
392  return true;
393  } else
394 #endif
395  {
397  _cs_assert();
398 
399  switch(_desc.mode){
400 
401  case SPI_TRANSFER_DMA:
402  if((out==NULL || ADDRESS_IN_RAM(out)) && (recv==NULL || ADDRESS_IN_RAM(recv)) ) {
403  setup_dma_transfer(out, recv, len);
404  return do_transfer(true, len)==0;
405  }
406 
407  // no break;
408  case SPI_TRANSFER_INTR: // interrupts
411  return do_transfer(false, len)==0;
412 
413  case SPI_TRANSFER_POLL: // polling
414  default:
415  if (out != NULL && recv !=NULL && len) {
416  for (uint16_t i = 0; i < len; i++) {
417  recv[i] = _transfer(out[i]);
418  }
419  }
420  _cs_release();
421  return true;
422  }
423  }
424  return false;
425 }
426 
427 
430 {
431  const SPIDesc *desc = nullptr;
432 
433  /* Find the bus description in the table */
434  for (uint8_t i = 0; i < F4Light_SPI_DEVICE_NUM_DEVICES; i++) {
435  if (!strcmp(spi_device_table[i].name, name)) {
436  desc = &spi_device_table[i];
437  break;
438  }
439  }
440 
441  if (!desc) {
442  AP_HAL::panic("SPI: invalid device name");
443  }
444 
446 }
447 
448 
449 SPIDevice::SPIDevice(const SPIDesc &device_desc)
450  : _desc(device_desc)
451  , _initialized(false)
452  , _completion_cb(0)
453 
454 {
457  if (!_cs) {
458  AP_HAL::panic("SPI: wrong CS pin");
459  }
460  } else {
461  _cs = NULL; // caller itself controls CS
462  }
463 }
464 
466  if ( dev->SPIx == SPI1)
467  return &board_spi_pins[0];
468  else if (dev->SPIx == SPI2)
469  return &board_spi_pins[1];
470  else if (dev->SPIx == SPI3)
471  return &board_spi_pins[2];
472  else {
473  assert_param(0);
474  return NULL;
475  }
476 }
477 
479 {
480 
481  spi_baud_rate rate;
482 
483  switch(freq) {
484  case SPI_36MHZ:
485  rate = SPI_BAUD_PCLK_DIV_2;
486  byte_time = 1; // time in 0.25uS units
487  break;
488  case SPI_18MHZ:
489  rate = SPI_BAUD_PCLK_DIV_4;
490  byte_time = 2;
491  break;
492  case SPI_9MHZ:
493  rate = SPI_BAUD_PCLK_DIV_8;
494  byte_time = 4;
495  break;
496  case SPI_4_5MHZ:
497  rate = SPI_BAUD_PCLK_DIV_16;
498  byte_time = 8;
499  break;
500  case SPI_2_25MHZ:
501  rate = SPI_BAUD_PCLK_DIV_32;
502  byte_time = 16;
503  break;
504  case SPI_1_125MHZ:
505  rate = SPI_BAUD_PCLK_DIV_64;
506  byte_time = 32;
507  break;
508  case SPI_562_500KHZ:
509  rate = SPI_BAUD_PCLK_DIV_128;
510  byte_time = 64;
511  break;
512  case SPI_281_250KHZ:
513  rate = SPI_BAUD_PCLK_DIV_256;
514  byte_time = 128;
515  break;
516  case SPI_140_625KHZ:
517  rate = SPI_BAUD_PCLK_DIV_256;
518  byte_time = 255;
519  break;
520  default:
521  rate = SPI_BAUD_PCLK_DIV_32;
522  byte_time = 16;
523  break;
524  }
525  return rate;
526 }
527 
528 
530  const Spi_DMA &dp = _desc.dev->dma;
531 
532 // check for DMA not busy before use
533  uint32_t t = hal_micros();
534  while(dma_is_stream_enabled(dp.stream_rx) || dma_is_stream_enabled(dp.stream_tx) ) { // wait for previous transfer termination
535  if(hal_micros() - t > 1000) break; // DMA transfer can't be more than 1ms
536  hal_yield(0);
537  }
538 
540 }
541 
542 
543 // DMA dummy workplace
544 static uint32_t rw_workbyte[] = { 0xffff }; // not in stack!
545 
546 void SPIDevice::setup_dma_transfer(const uint8_t *out, const uint8_t *recv, uint32_t btr){
547  DMA_InitType DMA_InitStructure;
548 
549  const Spi_DMA &dp = _desc.dev->dma;
550  uint32_t memory_inc;
551 
553 
555 
556 
557  DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)(&(_desc.dev->SPIx->DR));
558  DMA_InitStructure.DMA_BufferSize = btr;
559 
560  DMA_InitStructure.DMA_FIFO_flags = DMA_FIFOThreshold_Full | DMA_FIFOMode_Disable; // TODO use FIFO on large transfers
561 
562  // receive stream
563  if(recv) {
564  DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)recv;
565  memory_inc = DMA_CR_MINC;
566  } else {
567  DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)rw_workbyte;
568  memory_inc = 0;
569  }
570 
571  DMA_InitStructure.DMA_flags = DMA_CR_MSIZE_8BITS | DMA_CR_PSIZE_8BITS |
573  DMA_CR_DIR_P2M | memory_inc |
574  dp.channel | _desc.prio;
575  dma_init_transfer(dp.stream_rx, &DMA_InitStructure);
576 
577  // transmit stream
578  if(out) {
579  DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)out;
580  memory_inc = DMA_CR_MINC;
581  } else {
582  DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)rw_workbyte;
583  memory_inc = 0;
584  }
585  DMA_InitStructure.DMA_flags = DMA_CR_MSIZE_8BITS | DMA_CR_PSIZE_8BITS |
587  DMA_CR_DIR_M2P | memory_inc |
588  dp.channel | _desc.prio;
589  dma_init_transfer(dp.stream_tx, &DMA_InitStructure);
590 
591  dma_enable(dp.stream_rx); dma_enable(dp.stream_tx); // run them both!
592 
593  // we attach interrupt on RX channel's TransferComplete, so at ISR time bus will be free
595 }
596 
598  spi_enable_dma_req(_desc.dev, SPI_DMAreq_Rx | SPI_DMAreq_Tx); /* Enable SPI TX/RX request */
599 }
600 
601 
603  const Spi_DMA &dp = _desc.dev->dma;
604 
606  dma_detach_interrupt(dp.stream_rx); // we attach interrupt each request
607 
608  // Disable SPI RX/TX request
610 
612 }
613 
615  disable_dma();
616 
617  if(_desc.dev->state->len) {
618  memmove(_desc.dev->state->dst, &buffer[_desc.bus-1][0], _desc.dev->state->len);
619  _desc.dev->state->len=0; // once
620  }
621 
622  _send_len = 0; // send done
623 
624 // we attach interrupt on RX channel's TransferComplete, so at ISR bus will be free
625 
626  if(_recv_len) { // now we should program DMA for receive or turn on ISR mode receiving if can't DMA
627  (void)_desc.dev->SPIx->DR; // read fake data out
628  // now we should set up DMA transfer
629 
630  spi_wait_busy(_desc.dev); // just for case - RX transfer is finished
631 
632  delay_ns100(3); // small delay between TX and RX, to give the chip time to think over domestic affairs
633  // for slow devices which need a time between address and data
634  // 200ns uses setup_dma_transfer() itself
635 
636  bool can_dma = false;
637  uint8_t *recv = _recv_address;
638  uint16_t len = _recv_len;
639  uint8_t nb = _desc.bus-1;
640 
641  if(ADDRESS_IN_RAM(recv)){ //not in CCM
642  _desc.dev->state->len=0;
643  can_dma=true;
644  }else if(len<=SPI_BUFFER_SIZE && buffer[nb]){
645  _desc.dev->state->len=len;
646  _desc.dev->state->dst=recv;
647  recv = buffer[nb];
648  can_dma=true;
649  }
650  if(can_dma){
652  spi_disable_irq(_desc.dev, SPI_RXNE_INTERRUPT); // disable RXNE interrupt, TXE already disabled
653  setup_dma_transfer(NULL, recv, len);
654  _recv_len = 0; // receive by DMA
656  } else {
657  _isr_mode = SPI_ISR_RECEIVE; // just receive
659  spi_enable_irq(_desc.dev, SPI_TXE_INTERRUPT); // enable - will be interrupt just immediate
660  }
661  } else { // all done
662  isr_transfer_finish(); // releases SPI bus
663  }
664 }
665 
666 
668  if(_cs) {
669  _cs->mode(OUTPUT);
670  _cs_release(); // do not hold the SPI bus initially
671  }
672 
673  _completion_cb=0;
674 
675  const spi_pins *pins = dev_to_spi_pins(_desc.dev);
676 
677  if (!pins || pins->sck > BOARD_NR_GPIO_PINS || pins->mosi > BOARD_NR_GPIO_PINS || pins->miso > BOARD_NR_GPIO_PINS) {
678  return;
679  }
680 
681 #ifdef BOARD_SOFTWARE_SPI
682  if(_desc.mode == SPI_TRANSFER_SOFT) { //software
683 
684  { // isolate p
685  const stm32_pin_info &p = PIN_MAP[pins->sck];
686 
687  const gpio_dev *sck_dev = p.gpio_device;
688  uint8_t sck_bit = p.gpio_bit;
689 
690  gpio_set_mode(sck_dev, sck_bit, GPIO_OUTPUT_PP);
691  gpio_set_speed(sck_dev, sck_bit, GPIO_speed_100MHz);
692  gpio_write_bit(sck_dev, sck_bit, 1); // passive SCK high
693 
694 
695  sck_port = sck_dev->GPIOx;
696  sck_pin = 1<<sck_bit;
697  }
698 
699  { // isolate p
700  const stm32_pin_info &p = PIN_MAP[pins->mosi];
701 
702  const gpio_dev *mosi_dev = p.gpio_device;
703  uint8_t mosi_bit = p.gpio_bit;
704  gpio_set_mode(mosi_dev, mosi_bit, GPIO_OUTPUT_PP);
705  gpio_set_speed(mosi_dev, mosi_bit, GPIO_speed_100MHz);
706  gpio_write_bit(mosi_dev, mosi_bit, 1); // passive MOSI high
707 
708  mosi_port = mosi_dev->GPIOx;
709  mosi_pin = 1<<mosi_bit;
710  }
711 
712  { // isolate p
713  const stm32_pin_info &p = PIN_MAP[pins->miso];
714 
715  const gpio_dev *miso_dev = p.gpio_device;
716  uint8_t miso_bit = p.gpio_bit;
717  gpio_set_mode(miso_dev, miso_bit, GPIO_INPUT_PU);
718  gpio_set_speed(miso_dev, miso_bit, GPIO_speed_100MHz);
719 
720  miso_port = miso_dev->GPIOx;
721  miso_pin = 1<<miso_bit;
722  }
723 
724  } else
725 #endif
726  {
727  spi_init(_desc.dev); // disable device
728 
729  const stm32_pin_info &miso = PIN_MAP[pins->miso];
731  miso.gpio_device, PIN_MAP[pins->sck].gpio_bit,
732  miso.gpio_bit, PIN_MAP[pins->mosi].gpio_bit);
733 
734 
736  }
737  _initialized=true;
738 
739 }
740 
741 
743 {
744 //* this requires for 1-byte transfers
745  if(owner[_desc.bus-1] != this) { // bus was in use by another driver so need reinit
746  _initialized=false;
747  }
748 
749  if(!_initialized) {
750  init();
751  if(!_initialized) return false;
752  owner[_desc.bus-1] = this; // Got it!
753  }
754 //*/
755 
756  switch (speed) {
759  break;
761  default:
763  break;
764  }
765 
766  return true;
767 }
768 
769 
770 // start transfer and wait until it finished
771 uint8_t SPIDevice::do_transfer(bool is_DMA, uint32_t nbytes)
772 {
773 
774 #ifdef DEBUG_SPI
775 // spi_trans_ptr=0; // each transfer from start
776 
777  spi_trans &p = spi_trans_array[spi_trans_ptr];
778 
779  p.time = hal_micros();
780  p.dev = _desc.dev;
781  p.send_len = _send_len;
782  p.recv_len = _recv_len;
783  p.dummy_len=_dummy_len;
784  p.data = *_send_address;
785  p.cr2 = 0;
786  p.sr1 = 0;
787  p.mode = _isr_mode;
788  p.act = 0xff;
789 
790  spi_trans_ptr++;
791  if(spi_trans_ptr>=SPI_LOG_SIZE) spi_trans_ptr=0;
792 #endif
793 
794  if(_completion_cb) {// we should call it after completion via interrupt
795  if(is_DMA) {
797  } else {
798  spi_enable_irq(_desc.dev, SPI_RXNE_TXE_INTERRUPTS );// enable both interrupts - will be interrupt just immediate
799  }
800  return 0; // all another in ISR
801  }
802 
803  // no callback - need to wait
804  uint32_t timeout = nbytes * 16; // time to transfer all data - 16uS per byte
805 
806  uint32_t t=hal_micros();
807 
809 
810  EnterCriticalSection; // we are in multitask so if task switch occures between enable and pause then all transfer occures before task will be paused
811  // so task will be paused after transfer and never be resumed - so will cause timeout
812 
813  if(_task) Scheduler::task_pause(timeout);
814 
815  if(is_DMA) { // Enable SPI TX/RX request
817  } else {
818  spi_enable_irq(_desc.dev, SPI_RXNE_TXE_INTERRUPTS); // enable both interrupts - will be interrupt just immediate
819  }
821 
822  while (hal_micros()-t < timeout && _desc.dev->state->busy) {
823  hal_yield(0); // пока ждем пусть другие работают.
824  }
825 
826  _task = NULL; // already resumed
827  if(_desc.dev->state->busy) { // timeout, so there was no ISR, so
828 #ifdef DEBUG_SPI
829  p.sr1=0x80;
830 #endif
831  if(is_DMA) disable_dma();
832  isr_transfer_finish(); // disable interrupts
833  }
834 
835  return (_send_len == 0 && _recv_len == 0)? 0 : 1;
836 }
837 
838 
841 
842  (void)_desc.dev->SPIx->DR; // read fake data out
843 }
844 
845 
846 
847 uint16_t SPIDevice::send_strobe(const uint8_t *buffer, uint16_t len){ // send in ISR and strobe each byte by CS
848  while(_desc.dev->state->busy) hal_yield(0); // wait for previous transfer finished
849 
851  _send_len = len;
852  _recv_len = 0;
854 
856 
857  _cs->_write(0);
858 
859  _desc.dev->state->busy=true;
860 
861  (void)_desc.dev->SPIx->DR; // read fake data out
862 //[ write out 1st byte to do RXNE interrupt
863  _send_len--; // write 1st byte to start transfer
864  uint8_t b = *_send_address++;
865  _desc.dev->SPIx->DR = b;
866 //]
867 
868  (void) do_transfer(false, len);
869 
870  return _send_len;
871 }
872 
873 // gives received bytes to callback and returns when callback returns true but not linger than timeout (uS)
874 // so it works like wait for needed byte in ISR - but without wait
875 uint8_t SPIDevice::wait_for(uint8_t out, spi_WaitFunc cb, uint32_t dly){ // wait for needed byte in ISR
876  _send_len = out;
878  _recv_len = 0; // we shouldn't receive after wait
879  _compare_cb = cb;
880 
882 
883  uint32_t t = hal_micros();
884  _desc.dev->state->busy=true;
885 
886  // need to wait until transfer complete
888 
889  (void)_desc.dev->SPIx->DR; // read fake data out
890  _desc.dev->SPIx->DR = out; // start transfer and clear flag
891 
892  EnterCriticalSection; // prevent from task switch
893  if(_task) Scheduler::task_pause(dly); // if function called from task - store it and pause
894 
895  spi_enable_irq(_desc.dev, SPI_RXNE_TXE_INTERRUPTS); // enable both - will be interrupt on next line
897 
898  while (hal_micros() - t < dly && _desc.dev->state->busy) {
899  hal_yield(0);
900  }
901 
902  _task = NULL; // already resumed
903  if(_desc.dev->state->busy) isr_transfer_finish(); // timeout
904  return _recv_data;
905 }
906 
907 // releases SPI bus after transfer finished, call callback and resume task
910 
912 
913  while (spi_is_rx_nonempty(_desc.dev)) { // read out fake data for TX only transfers
914  (void)spi_rx_reg(_desc.dev);
915  }
916 
917  _desc.dev->state->busy=false; // reset
918 
919  if(_task){ // resume paused task
920  Scheduler::task_resume(_task); // task will be resumed having very high priority & force
921  // context switch just after return from ISR so task will get a tick
922  _task=NULL;
923  }
924 
925  spi_wait_busy(_desc.dev); // just for case - we already after last RXNE
926  if(_isr_mode != SPI_ISR_COMPARE) {
927  _cs_release(); // free bus
928  }
929 
930  Handler h;
931  if((h=_completion_cb)) {
932  _completion_cb=0; // only once and BEFORE call itself because IOC can do new transfer
933 
934  revo_call_handler(h, (uint32_t)&_desc);
935  }
936 }
937 
939 #ifdef DEBUG_SPI
940  spi_trans &p = spi_trans_array[spi_trans_ptr];
941 
942  p.time = hal_micros();
943  p.dev = _desc.dev;
944  p.send_len = _send_len;
945  p.recv_len = _recv_len;
946  p.dummy_len=_dummy_len;
947  p.cr2 = _desc.dev->SPIx->CR2;
948  p.sr1 = _desc.dev->SPIx->SR;
949  p.mode = _isr_mode;
950  p.act = 0;
951 
952  spi_trans_ptr++;
953  if(spi_trans_ptr>=SPI_LOG_SIZE) spi_trans_ptr=0;
954 #endif
955 
956 
958 #ifdef DEBUG_SPI
959  p.act |= 1;
960 #endif
961  switch(_isr_mode) {
962  case SPI_ISR_NONE:
963  (void)_desc.dev->SPIx->DR; // reset RXNE
964  spi_disable_irq(_desc.dev, SPI_TXE_INTERRUPT); // disable TXE interrupt
965  _isr_mode=SPI_ISR_FINISH; // should releases SPI bus after last RXNE is set
966  break;
967 
968  case SPI_ISR_SEND:
969  case SPI_ISR_SEND_DMA:
970  if(_send_len) {
971  _send_len--;
972  _desc.dev->SPIx->DR = *_send_address++;
973  } else { // all sent
974  // now we in 1 byte till bus release, so wait for RXNE
975 
976  spi_disable_irq(_desc.dev, SPI_TXE_INTERRUPT); // disable TXE interrupt
977 
978  if(_recv_len) {
979  if(_isr_mode==SPI_ISR_SEND) {
980  _isr_mode=SPI_ISR_WAIT_RX; // switch receive mode after receiving of fake RX byte
981  } else if(_isr_mode==SPI_ISR_SEND_DMA) {
982  _isr_mode=SPI_ISR_WAIT_RX_DMA; // will switch to DMA receive mode after receiving of fake RX byte
983  } else {
984  _isr_mode=SPI_ISR_FINISH; // should release SPI bus after last RXNE is set
985  }
986  } else {
987  _isr_mode=SPI_ISR_FINISH; // should release SPI bus after last RXNE is set
988  }
989  }
990  break;
991 
992  case SPI_ISR_RXTX:
993  _desc.dev->SPIx->DR = *_send_address++;
994  break;
995 
996  case SPI_ISR_RECEIVE:
997  if(_recv_len > 1) { // not on last byte
998  _desc.dev->SPIx->DR = 0xFF; // dummy byte
999  } else {
1000  spi_disable_irq(_desc.dev, SPI_TXE_INTERRUPT); // disable TXE interrupt
1001  }
1002  break;
1003 
1004  case SPI_ISR_COMPARE:
1005  case SPI_ISR_STROBE:
1006  default:
1007  spi_disable_irq(_desc.dev, SPI_TXE_INTERRUPT); // disable unneeded TXE interrupt
1008  break;
1009  }
1010  }
1011 
1012  if(spi_is_rx_nonempty(_desc.dev) /* && spi_is_irq_enabled(_desc.dev, SPI_RXNE_INTERRUPT) */) {
1013 #ifdef DEBUG_SPI
1014  p.act |= 2;
1015 #endif
1016 
1017  switch(_isr_mode) {
1018 
1019  case SPI_ISR_STROBE: {
1020  (void)_desc.dev->SPIx->DR; // read fake data out
1021  if(_send_len){
1023  delay_ns100(1);
1024  _cs->_write(1);
1025  delay_ns100(1);
1026  _send_len--;
1027  uint8_t b = *_send_address++;
1028  _cs->_write(0);
1029  delay_ns100(1);
1030  _desc.dev->SPIx->DR = b;
1031  } else {
1032  isr_transfer_finish(); // releases SPI bus after transfer complete
1033  }
1034  }
1035  break;
1036 
1037  case SPI_ISR_SEND:
1038  case SPI_ISR_SEND_DMA:
1039  (void)_desc.dev->SPIx->DR; // read fake data out
1040  _dummy_len--; // and count them
1041  break;
1042 
1043  case SPI_ISR_RECEIVE:
1044  if(_recv_len){
1045  _recv_len--;
1046  *_recv_address++ = _desc.dev->SPIx->DR;
1047  }
1048  if(_recv_len==0) { // last byte received
1049  isr_transfer_finish(); // releases SPI bus after last RXNE is set
1050  }
1051  break;
1052 
1053  case SPI_ISR_RXTX:
1054  *_recv_address++ = _desc.dev->SPIx->DR;
1055  _send_len--;
1056  if(!_send_len) { // readed the last byte
1057  isr_transfer_finish(); // releases SPI bus
1058  }
1059  break;
1060 
1061  case SPI_ISR_COMPARE:
1062  _recv_data = _desc.dev->SPIx->DR;
1063 
1064 #ifdef DEBUG_SPI
1065  p.data = _recv_data;
1066  p.cb = _compare_cb;
1067 #endif
1068 
1069  if(_compare_cb(_recv_data) ) { // ok
1070  if(_recv_len){
1071  _isr_mode = SPI_ISR_RECEIVE; // we should receive after wait ?
1072  } else {
1073  _send_len=0; // mark transfer finished
1075  }
1076  } else { // do nothing - just skip byte
1077  _desc.dev->SPIx->DR = _send_len; // data to send in len, only when we need next byte
1078  }
1079  break;
1080 
1081  case SPI_ISR_WAIT_RX_DMA: // we just got last RXNE of transfer
1082  (void)_desc.dev->SPIx->DR; // read fake data out
1083  if(_dummy_len){
1084  _dummy_len--;
1085  }
1086  if(_dummy_len==0) { // this was a last dummy byte, now we should program DMA for receive or turn on ISR mode receiving if can't DMA
1087  // now we should set up DMA transfer
1088 
1089  bool can_dma = false;
1090  uint8_t *recv = _recv_address;
1091  uint16_t len = _recv_len;
1092  uint8_t nb = _desc.bus-1;
1093 
1094  delay_ns100(5); // small delay between TX and RX, to give the chip time to think over domestic affairs
1095 
1096  if(ADDRESS_IN_RAM(recv)){ //not in CCM
1097  _desc.dev->state->len=0;
1098  can_dma=true;
1099  }else if(len<=SPI_BUFFER_SIZE && buffer[nb]){
1100  _desc.dev->state->len=len;
1101  _desc.dev->state->dst=recv;
1102  recv = buffer[nb];
1103  can_dma=true;
1104  }
1105  if(can_dma){
1106 #ifdef DEBUG_SPI
1107  p.act |= 10;
1108 #endif
1109  spi_disable_irq(_desc.dev, SPI_RXNE_INTERRUPT); // disable RXNE interrupt, TXE already disabled
1110  setup_dma_transfer(NULL, recv, len);
1112  _recv_len = 0; // all done
1114  break;
1115  }
1116 
1117  }
1118  // no break! we can't receive via DMA so setup receive in ISR
1119 
1120  case SPI_ISR_WAIT_RX: // turn on ISR mode receiving
1121  (void)_desc.dev->SPIx->DR; // read fake data out
1122  if(_dummy_len){
1123  _dummy_len--;
1124  }
1125  if(_dummy_len==0) { // this was a last dummy byte, now we should receive
1126  _isr_mode = SPI_ISR_RECEIVE; // we should receive
1127  _desc.dev->SPIx->DR = 0xFF; // write dummy byte for 1st transfer
1128 
1129  _dummy_len = _recv_len-1; // set number of bytes to be sent
1130  if(_dummy_len) { // if we should send additional bytes
1131  spi_enable_irq(_desc.dev, SPI_TXE_INTERRUPT); // enable TXE interrupt
1132  }
1133  }
1134  break;
1135 
1136  case SPI_ISR_FINISH:
1137  (void)_desc.dev->SPIx->DR; // read fake data out
1138  if(_dummy_len){
1139  _dummy_len--;
1140  }
1141  if(_dummy_len) break; // not last byte
1142 
1143  case SPI_ISR_NONE:
1144  default:
1145  isr_transfer_finish(); // releases SPI bus
1146  break;
1147  }
1148  }
1149 }
1150 
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
const spi_dev *const dev
Definition: SPIDevice.h:65
static uint32_t rw_workbyte[]
Definition: SPIDevice.cpp:544
uint32_t DMA_flags
Definition: dma.h:275
void send(uint8_t out)
Definition: SPIDevice.cpp:178
uint8_t * _recv_address
Definition: SPIDevice.h:215
void mode(uint8_t output)
Definition: GPIO.cpp:155
static void spi_disable_dma_req(const spi_dev *dev, uint16_t SPI_DMAReq)
Definition: spi.h:289
#define BOARD_SPI3_MISO_PIN
Definition: board.h:63
const spi_pins * dev_to_spi_pins(const spi_dev *dev)
Definition: SPIDevice.cpp:465
uint16_t _dummy_len
Definition: SPIDevice.h:214
static void * owner[MAX_BUS_NUM]
Definition: SPIDevice.h:182
uint16_t _recv_len
Definition: SPIDevice.h:216
F4Light::Semaphore SPIDevice::_semaphores [MAX_BUS_NUM] IN_CCM
Definition: SPIDevice.cpp:56
DigitalSource * _cs
Definition: SPIDevice.h:178
#define LeaveCriticalSection
Definition: Scheduler.h:40
#define MIN_DMA_BYTES
uint16_t send_strobe(const uint8_t *buffer, uint16_t len)
Definition: SPIDevice.cpp:847
uint32_t DMA_PeripheralBaseAddr
Definition: dma.h:259
#define assert_param(expr)
#define BOARD_SPI1_MOSI_PIN
Definition: board.h:58
#define DMA_CR_MSIZE_8BITS
Definition: dma.h:126
uint16_t _send_len
Definition: SPIDevice.h:213
void setup_isr_transfer()
Definition: SPIDevice.cpp:839
#define DMA_CR_PBURST0
Definition: dma.h:110
void spi_set_speed(const spi_dev *dev, uint16_t baudPrescaler)
Definition: spi.c:205
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static void spi_attach_interrupt(const spi_dev *dev, Handler handler)
Definition: spi.h:295
void setup_dma_transfer(const uint8_t *send, const uint8_t *recv, uint32_t btr)
Definition: SPIDevice.cpp:546
SPIFrequency lowspeed
Definition: SPIDevice.h:69
SPI_ISR_MODE _isr_mode
Definition: SPIDevice.h:218
#define MAX_BUS_NUM
Definition: SPIDevice.h:34
static void spi_wait_busy(const spi_dev *dev)
Definition: spi.h:275
static void * get_current_task()
Definition: Scheduler.h:299
static void task_resume(void *h)
Definition: Scheduler.h:321
Definition: GPIO.h:35
void dma_clear_isr_bits(dma_stream stream)
Clear the ISR status bits for a given DMA stream.
Definition: dma.c:237
static F4Light::Semaphore _semaphores[MAX_BUS_NUM]
Definition: SPIDevice.h:181
spi_WaitFunc _compare_cb
Definition: SPIDevice.h:219
GPIO_TypeDef * GPIOx
Definition: gpio_hal.h:54
uint32_t hal_micros()
Definition: Scheduler.cpp:1434
static void spi_enable_dma_req(const spi_dev *dev, uint16_t SPI_DMAReq)
Definition: spi.h:284
const char * name
Definition: BusTest.cpp:11
static AP_HAL::OwnPtr< F4Light::SPIDevice > _get_device(const char *name)
Definition: SPIDevice.cpp:429
Definition: spi.h:15
void spi_init(const spi_dev *dev)
Initialize and reset a SPI device.
Definition: spi.c:57
uint8_t(* spi_WaitFunc)(uint8_t b)
Definition: SPIDevice.h:48
void isr_transfer_finish()
Definition: SPIDevice.cpp:908
const SPIDesc & _desc
Definition: SPIDevice.h:176
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
const uint8_t * _send_address
Definition: SPIDevice.h:212
static uint8_t * buffer[MAX_BUS_NUM]
Definition: SPIDevice.h:183
#define DMA_FIFOMode_Disable
Definition: dma.h:154
#define SPI_DMAreq_Tx
Definition: spi.h:93
void start_dma_transfer()
Definition: SPIDevice.cpp:597
uint16_t len
Definition: spi.h:24
#define BOARD_SPI2_MISO_PIN
Definition: board.h:60
static uint8_t spi_rx_reg(const spi_dev *dev)
Definition: spi.h:259
uint8_t do_transfer(bool is_DMA, uint32_t nbytes)
Definition: SPIDevice.cpp:771
SPIFrequency
Definition: SPIDevice.h:36
#define BOARD_SPI3_MOSI_PIN
Definition: board.h:62
int spimaster_transfer(const spi_dev *dev, const uint8_t *txbuf, uint16_t txcount, uint8_t *rxbuf, uint16_t rxcount)
Definition: spi.c:219
const SPIDesc spi_device_table[]
static void spi_detach_interrupt(const spi_dev *dev)
Definition: spi.h:306
Spi_DMA dma
Definition: spi.h:34
SPI_transferMode mode
Definition: SPIDevice.h:71
bool set_speed(AP_HAL::Device::Speed speed) override
Definition: SPIDevice.cpp:742
dma_stream stream_rx
Definition: spi.h:17
uint8_t dma_is_stream_enabled(dma_stream stream)
Check if a DMA stream is enabled.
Definition: dma.c:230
dma_stream stream_tx
Definition: spi.h:18
uint16_t cs_pin
Definition: SPIDevice.h:68
#define BOARD_SPI2_MOSI_PIN
Definition: board.h:61
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
uint32_t prio
Definition: SPIDevice.h:72
static void spi_disable_irq(const spi_dev *dev, spi_interrupt interrupt_flags)
Definition: spi.h:241
#define DMA_FIFOThreshold_Full
Definition: dma.h:160
static uint8_t spi_is_busy(const spi_dev *dev)
Definition: spi.h:271
uint8_t * dst
Definition: spi.h:23
#define BOARD_SPI2_SCK_PIN
Definition: board.h:59
static const spi_pins board_spi_pins[]
Definition: SPIDevice.cpp:37
volatile bool busy
Definition: spi.h:25
static int state
Definition: Util.cpp:20
static void spi_master_enable(const spi_dev *dev, spi_baud_rate baudPrescaler, spi_mode mode, uint16_t bitorder)
Configure GPIO bit modes for use as a SPI port&#39;s pins.
Definition: spi.h:163
uint32_t DMA_FIFO_flags
Definition: dma.h:270
void dma_detach_interrupt(dma_stream stream)
Detach a DMA transfer interrupt handler.
Definition: dma.c:132
static bool spi_is_irq_enabled(const spi_dev *dev, uint32_t interrupt_flags)
Definition: spi.h:246
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: SPIDevice.cpp:188
static uint8_t spi_is_tx_empty(const spi_dev *dev)
Definition: spi.h:263
#define BOARD_NR_GPIO_PINS
Definition: board.h:96
void * malloc(size_t size)
Definition: malloc.c:61
#define NULL
Definition: hal_types.h:59
#define DMA_CR_DIR_M2P
Definition: dma.h:138
static void spi_tx_reg(const spi_dev *dev, uint8_t val)
Definition: spi.h:267
Board-specific pin information.
#define BOARD_SPI1_MISO_PIN
Definition: board.h:57
uint32_t DMA_BufferSize
Definition: dma.h:265
void dma_disable(dma_stream stream)
Definition: dma.c:219
SPI_TypeDef * SPIx
Definition: spi.h:30
#define BOARD_SPI1_SCK_PIN
Definition: board.h:56
uint8_t _transfer(uint8_t data)
Definition: SPIDevice.cpp:159
void dma_init_transfer(dma_stream stream, DMA_InitType *v)
Definition: dma.c:144
#define SPI_DMAreq_Rx
Definition: spi.h:94
void dma_attach_interrupt(dma_stream stream, Handler handler, uint8_t flag)
Attach an interrupt to a DMA transfer.
Definition: dma.c:108
#define DMA_CR_DIR_P2M
Definition: dma.h:137
#define DMA_CR_TCIE
Definition: dma.h:142
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override
Definition: SPIDevice.cpp:368
void _write(uint8_t value)
Definition: GPIO.h:116
uint32_t channel
Definition: spi.h:16
uint32_t DMA_Memory0BaseAddr
Definition: dma.h:261
spi_baud_rate
SPI baud rate configuration, as a divisor of f_PCLK, the PCLK clock frequency.
Definition: spi.h:70
spi_mode sm
Definition: SPIDevice.h:67
Definition: spi.h:44
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
Definition: gpio_hal.h:161
void register_completion_callback(Handler h)
Definition: SPIDevice.cpp:138
void dma_init(dma_stream stream)
Initialize a DMA device.
Definition: dma.c:85
spi_baud_rate determine_baud_rate(SPIFrequency freq)
Definition: SPIDevice.cpp:478
#define BOARD_SPI3_SCK_PIN
Definition: board.h:64
SPIFrequency _speed
Definition: SPIDevice.h:179
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
spi_state * state
Definition: spi.h:35
uint64_t Handler
Definition: hal_types.h:19
static void task_pause(uint32_t t)
Definition: Scheduler.h:316
static void delay_ns100(uint32_t us)
Definition: delay.h:36
Handler _completion_cb
Definition: SPIDevice.h:207
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define DMA_CR_MINC
Definition: dma.h:134
static DigitalSource * get_channel(uint16_t pin)
Definition: GPIO.h:170
void revo_call_handler(Handler h, uint32_t arg)
Definition: Scheduler.cpp:1420
#define SPI_BUFFER_SIZE
Definition: SPIDevice.h:173
uint8_t gpio_bit
Definition: boards.h:92
#define EnterCriticalSection
Definition: Scheduler.h:39
static uint8_t spi_is_rx_nonempty(const spi_dev *dev)
Definition: spi.h:255
#define ADDRESS_IN_RAM(a)
Definition: hal_types.h:91
#define DMA_CR_PSIZE_8BITS
Definition: dma.h:130
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
uint8_t wait_for(uint8_t out, spi_WaitFunc cb, uint32_t dly)
Definition: SPIDevice.cpp:875
const gpio_dev *const gpio_device
Definition: boards.h:89
Definition: spi.h:29
void dma_enable(dma_stream stream)
Definition: dma.c:213
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
void spi_gpio_master_cfg(const spi_dev *dev, const gpio_dev *comm_dev, uint8_t sck_bit, uint8_t miso_bit, uint8_t mosi_bit)
Configure and enable a SPI device as bus master.
Definition: spi.c:92
SPIFrequency highspeed
Definition: SPIDevice.h:70
#define DMA_CR_MBURST0
Definition: dma.h:106
const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES
uint8_t _recv_data
Definition: SPIDevice.h:220
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115
static void spi_enable_irq(const spi_dev *dev, spi_interrupt interrupt_flags)
Definition: spi.h:237