drv_spi.c
Go to the documentation of this file.
1 /*
2  * This file is part of Cleanflight.
3  *
4  * Cleanflight is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * Cleanflight is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License
15  * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <stdbool.h>
19 #include <stdint.h>
20 
21 //#include <platform.h>
22 #include <stm32f10x.h>
23 
24 #include "drv_gpio.h"
25 
26 #include "drv_spi.h"
27 
28 #define UNUSED(x) (void)(x)
29 
30 #define USE_SPI_DEVICE_1
31 #define USE_SPI_DEVICE_2
32 
33 #ifdef USE_SPI_DEVICE_1
34 
35 #ifndef SPI1_GPIO
36 #define SPI1_GPIO GPIOA
37 #define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA
38 #define SPI1_NSS_PIN GPIO_Pin_4
39 #define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
40 #define SPI1_SCK_PIN GPIO_Pin_5
41 #define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
42 #define SPI1_MISO_PIN GPIO_Pin_6
43 #define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
44 #define SPI1_MOSI_PIN GPIO_Pin_7
45 #define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
46 #endif
47 
48 void initSpi1(void)
49 {
50  // Specific to the STM32F103
51  // SPI1 Driver
52  // PA4 14 SPI1_NSS
53  // PA5 15 SPI1_SCK
54  // PA6 16 SPI1_MISO
55  // PA7 17 SPI1_MOSI
56 
57  SPI_InitTypeDef spi;
58 
59  // Enable SPI1 clock
62 
63 #ifdef STM32F303xC
64  GPIO_InitTypeDef GPIO_InitStructure;
65 
67 
71 
72 #ifdef SPI1_NSS_PIN_SOURCE
74 #endif
75 
76  // Init pins
77  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
78  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
79  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
80 
81 #ifdef USE_SDCARD_SPI1
82  // Configure pins and pullups for SD-card use
83 
84  // No pull-up needed since we drive this pin as an output
85  GPIO_InitStructure.GPIO_Pin = SPI1_MOSI_PIN;
86  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
87  GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
88 
89  // Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
90  GPIO_InitStructure.GPIO_Pin = SPI1_MISO_PIN;
91  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
92  GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
93 
94  // In clock-low mode, STM32 manual says we should enable a pulldown to match
95  GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN;
96  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
97  GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
98 #else
99  // General-purpose pin config
100  GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
101  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
102  GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
103 #endif
104 
105 #ifdef SPI1_NSS_PIN
106  GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN;
107  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
108  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
109  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
110  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
111 
112  GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
113 #endif
114 #endif
115 
116 
117 
118  gpio_config_t gpio;
119 
120  // MOSI + SCK as output
121  gpio.mode = Mode_AF_PP;
122  gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
123  gpio.speed = Speed_50MHz;
124  gpioInit(SPI1_GPIO, &gpio);
125 
126  // MISO as input
127  gpio.pin = SPI1_MISO_PIN;
128  gpio.mode = Mode_IN_FLOATING;
129  gpioInit(SPI1_GPIO, &gpio);
130 
131 #ifdef SPI1_NSS_PIN
132  // NSS as gpio slave select
133  gpio.pin = SPI1_NSS_PIN;
134  gpio.mode = Mode_Out_PP;
135  gpioInit(SPI1_GPIO, &gpio);
136 #endif
137 
138 
139  // Init SPI1 hardware
141 
145  spi.SPI_NSS = SPI_NSS_Soft;
147  spi.SPI_CRCPolynomial = 7;
149 
150 #ifdef USE_SDCARD_SPI1
151  spi.SPI_CPOL = SPI_CPOL_Low;
152  spi.SPI_CPHA = SPI_CPHA_1Edge;
153 #else
154  spi.SPI_CPOL = SPI_CPOL_High;
155  spi.SPI_CPHA = SPI_CPHA_2Edge;
156 #endif
157 
158 #ifdef STM32F303xC
159  // Configure for 8-bit reads.
161 #endif
162 
163  SPI_Init(SPI1, &spi);
164  SPI_Cmd(SPI1, ENABLE);
165 
166 #ifdef SPI1_NSS_PIN
167  // Drive NSS high to disable connected SPI device.
169 #endif
170 }
171 #endif
172 
173 #ifndef SPI2_GPIO
174 #define SPI2_GPIO GPIOB
175 #define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
176 #define SPI2_NSS_PIN GPIO_Pin_12
177 #define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
178 #define SPI2_SCK_PIN GPIO_Pin_13
179 #define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
180 #define SPI2_MISO_PIN GPIO_Pin_14
181 #define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
182 #define SPI2_MOSI_PIN GPIO_Pin_15
183 #define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
184 
185 
186 void initSpi2(void)
187 {
188  // Specific to the STM32F103 / STM32F303 (AF5)
189  // SPI2 Driver
190  // PB12 25 SPI2_NSS
191  // PB13 26 SPI2_SCK
192  // PB14 27 SPI2_MISO
193  // PB15 28 SPI2_MOSI
194 
195  SPI_InitTypeDef spi;
196 
197  // Enable SPI2 clock
200 
201  gpio_config_t gpio;
202 
203  // MOSI + SCK as output
204  gpio.mode = Mode_AF_PP;
205  gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN;
206  gpio.speed = Speed_50MHz;
207  gpioInit(SPI2_GPIO, &gpio);
208 
209  // MISO as input
210  gpio.pin = SPI2_MISO_PIN;
211  gpio.mode = Mode_IN_FLOATING;
212  gpioInit(SPI2_GPIO, &gpio);
213 
214 #ifdef SPI2_NSS_PIN
215  // NSS as gpio slave select
216  gpio.pin = SPI2_NSS_PIN;
217  gpio.mode = Mode_Out_PP;
218  gpioInit(SPI2_GPIO, &gpio);
219 #endif
220 
221 
222  // Init SPI2 hardware
224 
228  spi.SPI_NSS = SPI_NSS_Soft;
230  spi.SPI_CRCPolynomial = 7;
232 
233 #ifdef USE_SDCARD_SPI2
234  spi.SPI_CPOL = SPI_CPOL_Low;
235  spi.SPI_CPHA = SPI_CPHA_1Edge;
236 #else
237  spi.SPI_CPOL = SPI_CPOL_High;
238  spi.SPI_CPHA = SPI_CPHA_2Edge;
239 #endif
240 
241 #ifdef STM32F303xC
242  // Configure for 8-bit reads.
244 #endif
245 
246  SPI_Init(SPI2, &spi);
247  SPI_Cmd(SPI2, ENABLE);
248 
249 #ifdef SPI2_NSS_PIN
250  // Drive NSS high to disable connected SPI device.
252 #endif
253 }
254 #endif
255 
256 #if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
257 
258 #ifndef SPI3_GPIO
259 #define SPI3_GPIO GPIOB
260 #define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
261 #define SPI3_NSS_GPIO GPIOA
262 #define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA
263 #define SPI3_NSS_PIN GPIO_Pin_15
264 #define SPI3_NSS_PIN_SOURCE GPIO_PinSource15
265 #define SPI3_SCK_PIN GPIO_Pin_3
266 #define SPI3_SCK_PIN_SOURCE GPIO_PinSource3
267 #define SPI3_MISO_PIN GPIO_Pin_4
268 #define SPI3_MISO_PIN_SOURCE GPIO_PinSource4
269 #define SPI3_MOSI_PIN GPIO_Pin_5
270 #define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5
271 #endif
272 
273 void initSpi3(void)
274 {
275  // Specific to the STM32F303 (AF6)
276  // SPI3 Driver
277  // PA15 38 SPI3_NSS
278  // PB3 39 SPI3_SCK
279  // PB4 40 SPI3_MISO
280  // PB5 41 SPI3_MOSI
281 
282  SPI_InitTypeDef spi;
283 
284  // Enable SPI3 clock
287 
288  GPIO_InitTypeDef GPIO_InitStructure;
289 
290  RCC_AHBPeriphClockCmd(SPI3_GPIO_PERIPHERAL, ENABLE);
291 
292  GPIO_PinAFConfig(SPI3_GPIO, SPI3_SCK_PIN_SOURCE, GPIO_AF_6);
293  GPIO_PinAFConfig(SPI3_GPIO, SPI3_MISO_PIN_SOURCE, GPIO_AF_6);
294  GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6);
295 
296 #ifdef SPI2_NSS_PIN_SOURCE
297  RCC_AHBPeriphClockCmd(SPI3_NNS_PERIPHERAL, ENABLE);
298  GPIO_PinAFConfig(SPI3_NNS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
299 #endif
300 
301  // Init pins
302  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
303  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
304  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
305 
306 #ifdef USE_SDCARD_SPI3
307  // Configure pins and pullups for SD-card use
308 
309  // No pull-up needed since we drive this pin as an output
310  GPIO_InitStructure.GPIO_Pin = SPI3_MOSI_PIN;
311  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
312  GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
313 
314  // Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
315  GPIO_InitStructure.GPIO_Pin = SPI3_MISO_PIN;
316  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
317  GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
318 
319  // In clock-low mode, STM32 manual says we should enable a pulldown to match
320  GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN;
321  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
322  GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
323 #else
324  // General-purpose pin config
325  GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_MOSI_PIN;
326  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
327  GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
328 #endif
329 
330 #ifdef SPI3_NSS_PIN
331  GPIO_InitStructure.GPIO_Pin = SPI3_NSS_PIN;
332  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
333  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
334  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
335  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
336 
337  GPIO_Init(SPI3_NSS_GPIO, &GPIO_InitStructure);
338 #endif
339 
340  // Init SPI hardware
342 
346  spi.SPI_NSS = SPI_NSS_Soft;
348  spi.SPI_CRCPolynomial = 7;
350 
351 #ifdef USE_SDCARD_SPI3
352  spi.SPI_CPOL = SPI_CPOL_Low;
353  spi.SPI_CPHA = SPI_CPHA_1Edge;
354 #else
355  spi.SPI_CPOL = SPI_CPOL_High;
356  spi.SPI_CPHA = SPI_CPHA_2Edge;
357 #endif
358 
359  // Configure for 8-bit reads.
361 
362  SPI_Init(SPI3, &spi);
363  SPI_Cmd(SPI3, ENABLE);
364 
365 #ifdef SPI3_NSS_PIN
366  // Drive NSS high to disable connected SPI device.
367  GPIO_SetBits(SPI3_NSS_GPIO, SPI3_NSS_PIN);
368 #endif
369 }
370 #endif
371 
372 bool spiInit(SPI_TypeDef *instance)
373 {
374 #if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3)))
375  UNUSED(instance);
376 #endif
377 
378 #ifdef USE_SPI_DEVICE_1
379  if (instance == SPI1) {
380  initSpi1();
381  return true;
382  }
383 #endif
384 #ifdef USE_SPI_DEVICE_2
385  if (instance == SPI2) {
386  initSpi2();
387  return true;
388  }
389 #endif
390 #if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
391  if (instance == SPI3) {
392  initSpi3();
393  return true;
394  }
395 #endif
396  return false;
397 }
398 
399 uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
400 {
401  uint16_t spiTimeout = 1000;
402 
403  while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
404  if ((spiTimeout--) == 0)
405  break;
406  }
407 
408 
409 
410  SPI_I2S_SendData(instance, data);
411 
412  spiTimeout = 1000;
413  while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET){
414  if ((spiTimeout--) == 0)
415  break;
416  }
417 
418  return ((uint8_t)SPI_I2S_ReceiveData(instance));
419 
420 }
421 
425 bool spiIsBusBusy(SPI_TypeDef *instance)
426 {
428 }
429 
430 void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
431 {
432  uint16_t spiTimeout = 1000;
433 
434  uint8_t b;
435  instance->DR;
436  while (len--) {
437  b = in ? *(in++) : 0xFF;
438  while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
439  if ((spiTimeout--) == 0)
440  break;
441  }
442 
443 
444  SPI_I2S_SendData(instance, b);
445 
446  spiTimeout = 1000;
447  while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
448  if ((spiTimeout--) == 0)
449  break;
450  }
451 
452  b = SPI_I2S_ReceiveData(instance);
453 
454  if (out)
455  *(out++) = b;
456  }
457 }
458 
459 
460 void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
461 {
462 #define BR_CLEAR_MASK 0xFFC7
463 
464  uint16_t tempRegister;
465 
466  SPI_Cmd(instance, DISABLE);
467 
468  tempRegister = instance->CR1;
469 
470  switch (divisor) {
471  case 2:
472  tempRegister &= BR_CLEAR_MASK;
473  tempRegister |= SPI_BaudRatePrescaler_2;
474  break;
475 
476  case 4:
477  tempRegister &= BR_CLEAR_MASK;
478  tempRegister |= SPI_BaudRatePrescaler_4;
479  break;
480 
481  case 8:
482  tempRegister &= BR_CLEAR_MASK;
483  tempRegister |= SPI_BaudRatePrescaler_8;
484  break;
485 
486  case 16:
487  tempRegister &= BR_CLEAR_MASK;
488  tempRegister |= SPI_BaudRatePrescaler_16;
489  break;
490 
491  case 32:
492  tempRegister &= BR_CLEAR_MASK;
493  tempRegister |= SPI_BaudRatePrescaler_32;
494  break;
495 
496  case 64:
497  tempRegister &= BR_CLEAR_MASK;
498  tempRegister |= SPI_BaudRatePrescaler_64;
499  break;
500 
501  case 128:
502  tempRegister &= BR_CLEAR_MASK;
503  tempRegister |= SPI_BaudRatePrescaler_128;
504  break;
505 
506  case 256:
507  tempRegister &= BR_CLEAR_MASK;
508  tempRegister |= SPI_BaudRatePrescaler_256;
509  break;
510  }
511 
512  instance->CR1 = tempRegister;
513 
514  SPI_Cmd(instance, ENABLE);
515 }
#define SPI2_SCK_PIN
Definition: drv_spi.c:178
#define SPI1_GPIO
Definition: drv_spi.c:36
uint16_t SPI_DataSize
Definition: stm32f4xx_spi.h:62
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
#define SPI1_NSS_PIN_SOURCE
Definition: drv_spi.c:39
#define SPI_NSS_Soft
#define SPI2_GPIO
Definition: drv_spi.c:174
GPIO_Mode mode
Definition: drv_gpio.h:63
uint16_t SPI_Mode
Definition: stm32f4xx_spi.h:59
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the Low Speed APB (APB1) peripheral clock.
#define SPI2
Definition: stm32f4xx.h:2050
GPIO_Speed speed
Definition: drv_gpio.h:64
bool spiIsBusBusy(SPI_TypeDef *instance)
Definition: drv_spi.c:425
#define SPI1
Definition: stm32f4xx.h:2087
#define SPI3
Definition: stm32f4xx.h:2051
#define SPI_Mode_Master
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx/I2Sx peripheral.
#define SPI2_NSS_PIN
Definition: drv_spi.c:176
uint16_t SPI_BaudRatePrescaler
Definition: stm32f4xx_spi.h:75
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
Definition: drv_spi.c:460
#define GPIO_AF_6
AF 6 selection.
uint16_t SPI_CPOL
Definition: stm32f4xx_spi.h:65
#define SPI_I2S_FLAG_BSY
#define SPI1_NSS_PIN
Definition: drv_spi.c:38
uint16_t SPI_Direction
Definition: stm32f4xx_spi.h:56
#define SPI1_SCK_PIN_SOURCE
Definition: drv_spi.c:41
uint16_t SPI_CRCPolynomial
Definition: stm32f4xx_spi.h:84
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
Deinitializes the SPIx peripheral registers to their default reset values.
void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Enables or disables the High Speed APB (APB2) peripheral clock.
void initSpi1(void)
Definition: drv_spi.c:48
#define SPI2_MOSI_PIN
Definition: drv_spi.c:182
#define SPI_BaudRatePrescaler_32
__IO uint16_t CR1
Definition: stm32f4xx.h:1582
#define SPI1_MISO_PIN
Definition: drv_spi.c:42
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Checks whether the specified SPI flag is set or not.
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
Definition: drv_spi.c:399
Serial Peripheral Interface.
Definition: stm32f4xx.h:1580
#define BR_CLEAR_MASK
void GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_InitStruct)
Initializes the GPIOx peripheral according to the specified parameters in the GPIO_InitStruct.
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
Definition: drv_gpio.c:56
#define SPI_BaudRatePrescaler_256
void initSpi2(void)
Definition: drv_spi.c:186
Definition: stm32f4xx.h:706
#define SPI_BaudRatePrescaler_16
#define GPIO_AF_5
AF 5 selection.
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
#define SPI_I2S_FLAG_TXE
uint16_t pin
Definition: drv_gpio.h:62
#define SPI_CPHA_2Edge
#define SPI_BaudRatePrescaler_2
SPI Init structure definition.
Definition: stm32f4xx_spi.h:54
uint16_t SPI_NSS
Definition: stm32f4xx_spi.h:71
#define SPI_Direction_2Lines_FullDuplex
#define SPI_CPHA_1Edge
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
Definition: drv_spi.c:430
#define SPI_I2S_FLAG_RXNE
#define SPI_DataSize_8b
void SPI_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral.
#define SPI_CPOL_High
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitTypeDef *SPI_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the SPI_InitStruct.
bool spiInit(SPI_TypeDef *instance)
Definition: drv_spi.c:372
#define SPI_BaudRatePrescaler_128
#define SPI_BaudRatePrescaler_64
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
#define SPI1_MOSI_PIN_SOURCE
Definition: drv_spi.c:45
uint16_t SPI_FirstBit
Definition: stm32f4xx_spi.h:81
#define UNUSED(x)
Definition: drv_spi.c:28
#define SPI1_MOSI_PIN
Definition: drv_spi.c:44
void SPI_RxFIFOThresholdConfig(SPI_TypeDef *SPIx, uint16_t SPI_RxFIFOThreshold)
Configures the FIFO reception threshold for the selected SPI.
#define SPI1_GPIO_PERIPHERAL
Definition: drv_spi.c:37
#define SPI_CPOL_Low
void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
Enables or disables the AHB peripheral clock.
#define SPI2_MISO_PIN
Definition: drv_spi.c:180
uint16_t SPI_CPHA
Definition: stm32f4xx_spi.h:68
#define SPI_RxFIFOThreshold_QF
#define SPI_FirstBit_MSB
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data)
Transmits a Data through the SPIx/I2Sx peripheral.
CMSIS Cortex-M3 Device Peripheral Access Layer Header File. This file contains all the peripheral reg...
__IO uint16_t DR
Definition: stm32f4xx.h:1588
void GPIO_SetBits(GPIO_TypeDef *GPIOx, uint16_t GPIO_Pin)
Sets the selected data port bits.
#define SPI1_SCK_PIN
Definition: drv_spi.c:40
#define SPI_BaudRatePrescaler_4
#define SPI_BaudRatePrescaler_8
#define SPI1_MISO_PIN_SOURCE
Definition: drv_spi.c:43


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46