stm32f10x_spi.c
Go to the documentation of this file.
1 
22 /* Includes ------------------------------------------------------------------*/
23 #include "stm32f10x_spi.h"
24 #include "stm32f10x_rcc.h"
25 
48 /* SPI SPE mask */
49 #define CR1_SPE_Set ((uint16_t)0x0040)
50 #define CR1_SPE_Reset ((uint16_t)0xFFBF)
51 
52 /* I2S I2SE mask */
53 #define I2SCFGR_I2SE_Set ((uint16_t)0x0400)
54 #define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF)
55 
56 /* SPI CRCNext mask */
57 #define CR1_CRCNext_Set ((uint16_t)0x1000)
58 
59 /* SPI CRCEN mask */
60 #define CR1_CRCEN_Set ((uint16_t)0x2000)
61 #define CR1_CRCEN_Reset ((uint16_t)0xDFFF)
62 
63 /* SPI SSOE mask */
64 #define CR2_SSOE_Set ((uint16_t)0x0004)
65 #define CR2_SSOE_Reset ((uint16_t)0xFFFB)
66 
67 /* SPI registers Masks */
68 #define CR1_CLEAR_Mask ((uint16_t)0x3040)
69 #define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040)
70 
71 /* SPI or I2S mode selection masks */
72 #define SPI_Mode_Select ((uint16_t)0xF7FF)
73 #define I2S_Mode_Select ((uint16_t)0x0800)
74 
75 /* I2S clock source selection masks */
76 #define I2S2_CLOCK_SRC ((uint32_t)(0x00020000))
77 #define I2S3_CLOCK_SRC ((uint32_t)(0x00040000))
78 #define I2S_MUL_MASK ((uint32_t)(0x0000F000))
79 #define I2S_DIV_MASK ((uint32_t)(0x000000F0))
80 
120 {
121  /* Check the parameters */
123 
124  if (SPIx == SPI1)
125  {
126  /* Enable SPI1 reset state */
128  /* Release SPI1 from reset state */
130  }
131  else if (SPIx == SPI2)
132  {
133  /* Enable SPI2 reset state */
135  /* Release SPI2 from reset state */
137  }
138  else
139  {
140  if (SPIx == SPI3)
141  {
142  /* Enable SPI3 reset state */
144  /* Release SPI3 from reset state */
146  }
147  }
148 }
149 
158 void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
159 {
160  uint16_t tmpreg = 0;
161 
162  /* check the parameters */
164 
165  /* Check the SPI parameters */
167  assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
168  assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
169  assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
170  assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
171  assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
173  assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
175 
176 /*---------------------------- SPIx CR1 Configuration ------------------------*/
177  /* Get the SPIx CR1 value */
178  tmpreg = SPIx->CR1;
179  /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
180  tmpreg &= CR1_CLEAR_Mask;
181  /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
182  master/salve mode, CPOL and CPHA */
183  /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
184  /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
185  /* Set LSBFirst bit according to SPI_FirstBit value */
186  /* Set BR bits according to SPI_BaudRatePrescaler value */
187  /* Set CPOL bit according to SPI_CPOL value */
188  /* Set CPHA bit according to SPI_CPHA value */
189  tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
190  SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |
191  SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |
192  SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
193  /* Write to SPIx CR1 */
194  SPIx->CR1 = tmpreg;
195 
196  /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
197  SPIx->I2SCFGR &= SPI_Mode_Select;
198 
199 /*---------------------------- SPIx CRCPOLY Configuration --------------------*/
200  /* Write to SPIx CRCPOLY */
201  SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
202 }
203 
219 void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
220 {
221  uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
222  uint32_t tmp = 0;
223  RCC_ClocksTypeDef RCC_Clocks;
224  uint32_t sourceclock = 0;
225 
226  /* Check the I2S parameters */
228  assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
229  assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
232  assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
233  assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
234 
235 /*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
236  /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
237  SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask;
238  SPIx->I2SPR = 0x0002;
239 
240  /* Get the I2SCFGR register value */
241  tmpreg = SPIx->I2SCFGR;
242 
243  /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
244  if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
245  {
246  i2sodd = (uint16_t)0;
247  i2sdiv = (uint16_t)2;
248  }
249  /* If the requested audio frequency is not the default, compute the prescaler */
250  else
251  {
252  /* Check the frame length (For the Prescaler computing) */
253  if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
254  {
255  /* Packet length is 16 bits */
256  packetlength = 1;
257  }
258  else
259  {
260  /* Packet length is 32 bits */
261  packetlength = 2;
262  }
263 
264  /* Get the I2S clock source mask depending on the peripheral number */
265  if(((uint32_t)SPIx) == SPI2_BASE)
266  {
267  /* The mask is relative to I2S2 */
268  tmp = I2S2_CLOCK_SRC;
269  }
270  else
271  {
272  /* The mask is relative to I2S3 */
273  tmp = I2S3_CLOCK_SRC;
274  }
275 
276  /* Check the I2S clock source configuration depending on the Device:
277  Only Connectivity line devices have the PLL3 VCO clock */
278 #ifdef STM32F10X_CL
279  if((RCC->CFGR2 & tmp) != 0)
280  {
281  /* Get the configuration bits of RCC PLL3 multiplier */
282  tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12);
283 
284  /* Get the value of the PLL3 multiplier */
285  if((tmp > 5) && (tmp < 15))
286  {
287  /* Multiplier is between 8 and 14 (value 15 is forbidden) */
288  tmp += 2;
289  }
290  else
291  {
292  if (tmp == 15)
293  {
294  /* Multiplier is 20 */
295  tmp = 20;
296  }
297  }
298  /* Get the PREDIV2 value */
299  sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1);
300 
301  /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */
302  sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2);
303  }
304  else
305  {
306  /* I2S Clock source is System clock: Get System Clock frequency */
307  RCC_GetClocksFreq(&RCC_Clocks);
308 
309  /* Get the source clock value: based on System Clock value */
310  sourceclock = RCC_Clocks.SYSCLK_Frequency;
311  }
312 #else /* STM32F10X_HD */
313  /* I2S Clock source is System clock: Get System Clock frequency */
314  RCC_GetClocksFreq(&RCC_Clocks);
315 
316  /* Get the source clock value: based on System Clock value */
317  sourceclock = RCC_Clocks.SYSCLK_Frequency;
318 #endif /* STM32F10X_CL */
319 
320  /* Compute the Real divider depending on the MCLK output state with a floating point */
321  if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
322  {
323  /* MCLK output is enabled */
324  tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5);
325  }
326  else
327  {
328  /* MCLK output is disabled */
329  tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5);
330  }
331 
332  /* Remove the floating point */
333  tmp = tmp / 10;
334 
335  /* Check the parity of the divider */
336  i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
337 
338  /* Compute the i2sdiv prescaler */
339  i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
340 
341  /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
342  i2sodd = (uint16_t) (i2sodd << 8);
343  }
344 
345  /* Test if the divider is 1 or 0 or greater than 0xFF */
346  if ((i2sdiv < 2) || (i2sdiv > 0xFF))
347  {
348  /* Set the default values */
349  i2sdiv = 2;
350  i2sodd = 0;
351  }
352 
353  /* Write to SPIx I2SPR register the computed value */
354  SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput));
355 
356  /* Configure the I2S with the SPI_InitStruct values */
357  tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \
358  (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
359  (uint16_t)I2S_InitStruct->I2S_CPOL))));
360 
361  /* Write to SPIx I2SCFGR */
362  SPIx->I2SCFGR = tmpreg;
363 }
364 
370 void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
371 {
372 /*--------------- Reset SPI init structure parameters values -----------------*/
373  /* Initialize the SPI_Direction member */
375  /* initialize the SPI_Mode member */
376  SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
377  /* initialize the SPI_DataSize member */
378  SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
379  /* Initialize the SPI_CPOL member */
380  SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
381  /* Initialize the SPI_CPHA member */
382  SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
383  /* Initialize the SPI_NSS member */
384  SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
385  /* Initialize the SPI_BaudRatePrescaler member */
387  /* Initialize the SPI_FirstBit member */
388  SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
389  /* Initialize the SPI_CRCPolynomial member */
390  SPI_InitStruct->SPI_CRCPolynomial = 7;
391 }
392 
398 void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
399 {
400 /*--------------- Reset I2S init structure parameters values -----------------*/
401  /* Initialize the I2S_Mode member */
402  I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
403 
404  /* Initialize the I2S_Standard member */
405  I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
406 
407  /* Initialize the I2S_DataFormat member */
408  I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
409 
410  /* Initialize the I2S_MCLKOutput member */
411  I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
412 
413  /* Initialize the I2S_AudioFreq member */
414  I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
415 
416  /* Initialize the I2S_CPOL member */
417  I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
418 }
419 
427 void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
428 {
429  /* Check the parameters */
432  if (NewState != DISABLE)
433  {
434  /* Enable the selected SPI peripheral */
435  SPIx->CR1 |= CR1_SPE_Set;
436  }
437  else
438  {
439  /* Disable the selected SPI peripheral */
440  SPIx->CR1 &= CR1_SPE_Reset;
441  }
442 }
443 
451 void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
452 {
453  /* Check the parameters */
456  if (NewState != DISABLE)
457  {
458  /* Enable the selected SPI peripheral (in I2S mode) */
459  SPIx->I2SCFGR |= I2SCFGR_I2SE_Set;
460  }
461  else
462  {
463  /* Disable the selected SPI peripheral (in I2S mode) */
464  SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset;
465  }
466 }
467 
482 void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
483 {
484  uint16_t itpos = 0, itmask = 0 ;
485  /* Check the parameters */
488  assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
489 
490  /* Get the SPI/I2S IT index */
491  itpos = SPI_I2S_IT >> 4;
492 
493  /* Set the IT mask */
494  itmask = (uint16_t)1 << (uint16_t)itpos;
495 
496  if (NewState != DISABLE)
497  {
498  /* Enable the selected SPI/I2S interrupt */
499  SPIx->CR2 |= itmask;
500  }
501  else
502  {
503  /* Disable the selected SPI/I2S interrupt */
504  SPIx->CR2 &= (uint16_t)~itmask;
505  }
506 }
507 
521 void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
522 {
523  /* Check the parameters */
526  assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
527  if (NewState != DISABLE)
528  {
529  /* Enable the selected SPI/I2S DMA requests */
530  SPIx->CR2 |= SPI_I2S_DMAReq;
531  }
532  else
533  {
534  /* Disable the selected SPI/I2S DMA requests */
535  SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq;
536  }
537 }
538 
547 void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data)
548 {
549  /* Check the parameters */
551 
552  /* Write in the DR register the data to be sent */
553  SPIx->DR = Data;
554 }
555 
564 {
565  /* Check the parameters */
567 
568  /* Return the data in the DR register */
569  return SPIx->DR;
570 }
571 
581 void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft)
582 {
583  /* Check the parameters */
585  assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
586  if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
587  {
588  /* Set NSS pin internally by software */
589  SPIx->CR1 |= SPI_NSSInternalSoft_Set;
590  }
591  else
592  {
593  /* Reset NSS pin internally by software */
595  }
596 }
597 
606 {
607  /* Check the parameters */
610  if (NewState != DISABLE)
611  {
612  /* Enable the selected SPI SS output */
613  SPIx->CR2 |= CR2_SSOE_Set;
614  }
615  else
616  {
617  /* Disable the selected SPI SS output */
618  SPIx->CR2 &= CR2_SSOE_Reset;
619  }
620 }
621 
631 void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize)
632 {
633  /* Check the parameters */
635  assert_param(IS_SPI_DATASIZE(SPI_DataSize));
636  /* Clear DFF bit */
637  SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b;
638  /* Set new DFF bit value */
639  SPIx->CR1 |= SPI_DataSize;
640 }
641 
648 {
649  /* Check the parameters */
651 
652  /* Enable the selected SPI CRC transmission */
653  SPIx->CR1 |= CR1_CRCNext_Set;
654 }
655 
664 {
665  /* Check the parameters */
668  if (NewState != DISABLE)
669  {
670  /* Enable the selected SPI CRC calculation */
671  SPIx->CR1 |= CR1_CRCEN_Set;
672  }
673  else
674  {
675  /* Disable the selected SPI CRC calculation */
676  SPIx->CR1 &= CR1_CRCEN_Reset;
677  }
678 }
679 
689 uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC)
690 {
691  uint16_t crcreg = 0;
692  /* Check the parameters */
694  assert_param(IS_SPI_CRC(SPI_CRC));
695  if (SPI_CRC != SPI_CRC_Rx)
696  {
697  /* Get the Tx CRC register */
698  crcreg = SPIx->TXCRCR;
699  }
700  else
701  {
702  /* Get the Rx CRC register */
703  crcreg = SPIx->RXCRCR;
704  }
705  /* Return the selected CRC register */
706  return crcreg;
707 }
708 
715 {
716  /* Check the parameters */
718 
719  /* Return the CRC polynomial register */
720  return SPIx->CRCPR;
721 }
722 
732 void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction)
733 {
734  /* Check the parameters */
736  assert_param(IS_SPI_DIRECTION(SPI_Direction));
737  if (SPI_Direction == SPI_Direction_Tx)
738  {
739  /* Set the Tx only mode */
740  SPIx->CR1 |= SPI_Direction_Tx;
741  }
742  else
743  {
744  /* Set the Rx only mode */
745  SPIx->CR1 &= SPI_Direction_Rx;
746  }
747 }
748 
766 FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
767 {
768  FlagStatus bitstatus = RESET;
769  /* Check the parameters */
771  assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
772  /* Check the status of the specified SPI/I2S flag */
773  if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET)
774  {
775  /* SPI_I2S_FLAG is set */
776  bitstatus = SET;
777  }
778  else
779  {
780  /* SPI_I2S_FLAG is reset */
781  bitstatus = RESET;
782  }
783  /* Return the SPI_I2S_FLAG status */
784  return bitstatus;
785 }
786 
804 void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
805 {
806  /* Check the parameters */
808  assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
809 
810  /* Clear the selected SPI CRC Error (CRCERR) flag */
811  SPIx->SR = (uint16_t)~SPI_I2S_FLAG;
812 }
813 
829 ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
830 {
831  ITStatus bitstatus = RESET;
832  uint16_t itpos = 0, itmask = 0, enablestatus = 0;
833 
834  /* Check the parameters */
836  assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
837 
838  /* Get the SPI/I2S IT index */
839  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
840 
841  /* Get the SPI/I2S IT mask */
842  itmask = SPI_I2S_IT >> 4;
843 
844  /* Set the IT mask */
845  itmask = 0x01 << itmask;
846 
847  /* Get the SPI_I2S_IT enable bit status */
848  enablestatus = (SPIx->CR2 & itmask) ;
849 
850  /* Check the status of the specified SPI/I2S interrupt */
851  if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus)
852  {
853  /* SPI_I2S_IT is set */
854  bitstatus = SET;
855  }
856  else
857  {
858  /* SPI_I2S_IT is reset */
859  bitstatus = RESET;
860  }
861  /* Return the SPI_I2S_IT status */
862  return bitstatus;
863 }
864 
883 void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
884 {
885  uint16_t itpos = 0;
886  /* Check the parameters */
888  assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
889 
890  /* Get the SPI IT index */
891  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
892 
893  /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */
894  SPIx->SR = (uint16_t)~itpos;
895 }
908 /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
void SPI_CalculateCRC(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the CRC value calculation of the transferred bytes.
FlagStatus
Definition: stm32f4xx.h:706
#define I2S_DataFormat_16b
uint16_t SPI_DataSize
Definition: stm32f4xx_spi.h:62
#define I2S_MUL_MASK
Definition: stm32f10x_spi.c:78
#define I2S_Mode_SlaveTx
#define IS_SPI_NSS_INTERNAL(INTERNAL)
#define I2S2_CLOCK_SRC
Definition: stm32f10x_spi.c:76
uint16_t SPI_Mode
Definition: stm32f4xx_spi.h:59
#define IS_SPI_I2S_GET_IT(IT)
#define SPI2
Definition: stm32f4xx.h:2050
#define IS_SPI_ALL_PERIPH(PERIPH)
FunctionalState
Definition: stm32f4xx.h:708
void SPI_TransmitCRC(SPI_TypeDef *SPIx)
Transmit the SPIx CRC value.
#define IS_SPI_I2S_CLEAR_FLAG(FLAG)
#define I2SCFGR_I2SE_Reset
Definition: stm32f10x_spi.c:54
#define SPI_Mode_Slave
#define SPI1
Definition: stm32f4xx.h:2087
#define SPI_DataSize_16b
#define IS_I2S_AUDIO_FREQ(FREQ)
#define SPI3
Definition: stm32f4xx.h:2051
#define IS_SPI_I2S_DMAREQ(DMAREQ)
uint16_t SPI_BaudRatePrescaler
Definition: stm32f4xx_spi.h:75
#define I2S_MCLKOutput_Disable
void SPI_I2S_DeInit(SPI_TypeDef *SPIx)
Deinitializes the SPIx peripheral registers to their default reset values (Affects also the I2Ss)...
uint16_t SPI_CPOL
Definition: stm32f4xx_spi.h:65
uint16_t I2S_Standard
Definition: stm32f4xx_spi.h:97
void SPI_I2S_SendData(SPI_TypeDef *SPIx, uint16_t Data)
Transmits a Data through the SPIx/I2Sx peripheral.
uint16_t SPI_Direction
Definition: stm32f4xx_spi.h:56
#define SPI_Direction_Tx
#define I2SCFGR_CLEAR_Mask
Definition: stm32f10x_spi.c:69
uint16_t SPI_CRCPolynomial
Definition: stm32f4xx_spi.h:84
#define SPI2_BASE
Definition: stm32f4xx.h:1898
__IO uint16_t CRCPR
Definition: stm32f4xx.h:1590
void assert_param(int val)
#define I2S_Mode_Select
Definition: stm32f10x_spi.c:73
#define SPI_Mode_Select
Definition: stm32f10x_spi.c:72
__IO uint16_t CR1
Definition: stm32f4xx.h:1582
#define CR1_CRCNext_Set
Definition: stm32f10x_spi.c:57
uint16_t I2S_Mode
Definition: stm32f4xx_spi.h:94
void SPI_I2S_ClearITPendingBit(SPI_TypeDef *SPIx, uint8_t SPI_I2S_IT)
Clears the SPIx CRC Error (CRCERR) interrupt pending bit.
#define IS_SPI_DIRECTION(DIRECTION)
#define IS_FUNCTIONAL_STATE(STATE)
Definition: stm32f4xx.h:709
void SPI_SSOutputCmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the SS output for the selected SPI.
Serial Peripheral Interface.
Definition: stm32f4xx.h:1580
#define I2S3_CLOCK_SRC
Definition: stm32f10x_spi.c:77
__IO uint16_t RXCRCR
Definition: stm32f4xx.h:1592
#define CR2_SSOE_Set
Definition: stm32f10x_spi.c:64
void SPI_NSSInternalSoftwareConfig(SPI_TypeDef *SPIx, uint16_t SPI_NSSInternalSoft)
Configures internally by software the NSS pin for the selected SPI.
#define CR2_SSOE_Reset
Definition: stm32f10x_spi.c:65
void SPI_StructInit(SPI_InitTypeDef *SPI_InitStruct)
Fills each SPI_InitStruct member with its default value.
FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Checks whether the specified SPI/I2S flag is set or not.
void SPI_DataSizeConfig(SPI_TypeDef *SPIx, uint16_t SPI_DataSize)
Configures the data size for the selected SPI.
Definition: stm32f4xx.h:706
enum FlagStatus ITStatus
#define IS_SPI_FIRST_BIT(BIT)
void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Forces or releases Low Speed APB (APB1) peripheral reset.
uint16_t SPI_I2S_ReceiveData(SPI_TypeDef *SPIx)
Returns the most recent received data by the SPIx/I2Sx peripheral.
#define SPI_NSSInternalSoft_Set
#define IS_I2S_DATA_FORMAT(FORMAT)
void I2S_Init(SPI_TypeDef *SPIx, I2S_InitTypeDef *I2S_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the I2S_InitStruct.
#define I2S_CPOL_Low
#define IS_I2S_CPOL(CPOL)
uint32_t I2S_AudioFreq
uint16_t I2S_MCLKOutput
#define IS_SPI_DATASIZE(DATASIZE)
#define SPI_BaudRatePrescaler_2
#define SPI_Direction_Rx
#define IS_I2S_MODE(MODE)
#define CR1_CRCEN_Reset
Definition: stm32f10x_spi.c:61
SPI Init structure definition.
Definition: stm32f4xx_spi.h:54
uint16_t SPI_NSS
Definition: stm32f4xx_spi.h:71
#define SPI_CRC_Rx
#define SPI_Direction_2Lines_FullDuplex
#define RCC
Definition: stm32f4xx.h:2122
#define IS_SPI_MODE(MODE)
#define HSE_Value
Definition: stm32f10x.h:528
#define SPI_CPHA_1Edge
#define I2S_Standard_Phillips
__IO uint16_t TXCRCR
Definition: stm32f4xx.h:1594
__IO uint16_t I2SPR
Definition: stm32f4xx.h:1598
#define IS_SPI_CPHA(CPHA)
#define SPI_NSSInternalSoft_Reset
#define CR1_SPE_Set
Definition: stm32f10x_spi.c:49
#define SPI_DataSize_8b
This file contains all the functions prototypes for the RCC firmware library.
#define CR1_CRCEN_Set
Definition: stm32f10x_spi.c:60
#define IS_I2S_STANDARD(STANDARD)
#define IS_SPI_I2S_GET_FLAG(FLAG)
uint16_t SPI_GetCRCPolynomial(SPI_TypeDef *SPIx)
Returns the CRC Polynomial register value for the specified SPI.
#define IS_SPI_23_PERIPH(PERIPH)
#define IS_SPI_I2S_CONFIG_IT(IT)
void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
Forces or releases High Speed APB (APB2) peripheral reset.
void SPI_I2S_ClearFlag(SPI_TypeDef *SPIx, uint16_t SPI_I2S_FLAG)
Clears the SPIx CRC Error (CRCERR) flag.
uint16_t SPI_FirstBit
Definition: stm32f4xx_spi.h:81
__IO uint16_t SR
Definition: stm32f4xx.h:1586
void I2S_StructInit(I2S_InitTypeDef *I2S_InitStruct)
Fills each I2S_InitStruct member with its default value.
#define IS_SPI_CPOL(CPOL)
I2S Init structure definition.
Definition: stm32f4xx_spi.h:91
__IO uint16_t I2SCFGR
Definition: stm32f4xx.h:1596
#define SPI_CPOL_Low
#define CR1_CLEAR_Mask
Definition: stm32f10x_spi.c:68
uint16_t SPI_CPHA
Definition: stm32f4xx_spi.h:68
#define CR1_SPE_Reset
Definition: stm32f10x_spi.c:50
#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER)
ITStatus SPI_I2S_GetITStatus(SPI_TypeDef *SPIx, uint8_t SPI_I2S_IT)
Checks whether the specified SPI/I2S interrupt has occurred or not.
void SPI_BiDirectionalLineConfig(SPI_TypeDef *SPIx, uint16_t SPI_Direction)
Selects the data transfer direction in bi-directional mode for the specified SPI. ...
#define SPI_FirstBit_MSB
#define I2SCFGR_I2SE_Set
Definition: stm32f10x_spi.c:53
void I2S_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral (in I2S mode).
uint16_t I2S_DataFormat
#define I2S_MCLKOutput_Enable
void RCC_GetClocksFreq(RCC_ClocksTypeDef *RCC_Clocks)
Returns the frequencies of different on chip clocks; SYSCLK, HCLK, PCLK1 and PCLK2.
#define IS_SPI_DIRECTION_MODE(MODE)
#define IS_SPI_NSS(NSS)
__IO uint16_t DR
Definition: stm32f4xx.h:1588
#define SPI_NSS_Hard
#define IS_SPI_CRC(CRC)
#define IS_I2S_MCLK_OUTPUT(OUTPUT)
#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL)
void SPI_I2S_DMACmd(SPI_TypeDef *SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
Enables or disables the SPIx/I2Sx DMA interface.
#define I2S_DIV_MASK
Definition: stm32f10x_spi.c:79
void SPI_I2S_ITConfig(SPI_TypeDef *SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
Enables or disables the specified SPI/I2S interrupts.
void SPI_Init(SPI_TypeDef *SPIx, SPI_InitTypeDef *SPI_InitStruct)
Initializes the SPIx peripheral according to the specified parameters in the SPI_InitStruct.
#define IS_SPI_I2S_CLEAR_IT(IT)
uint16_t SPI_GetCRC(SPI_TypeDef *SPIx, uint8_t SPI_CRC)
Returns the transmit or the receive CRC register value for the specified SPI.
This file contains all the functions prototypes for the SPI firmware library.
void SPI_Cmd(SPI_TypeDef *SPIx, FunctionalState NewState)
Enables or disables the specified SPI peripheral.
#define I2S_AudioFreq_Default
__IO uint16_t CR2
Definition: stm32f4xx.h:1584


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