Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F30x_StdPeriph_Driver / src / stm32f30x_spi.c
blobf6a5ca5cde8c1146b5c3156fd9d7be26f421d1fd
1 /**
2 ******************************************************************************
3 * @file stm32f30x_spi.c
4 * @author MCD Application Team
5 * @version V1.1.1
6 * @date 04-April-2014
7 * @brief This file provides firmware functions to manage the following
8 * functionalities of the Serial peripheral interface (SPI):
9 * + Initialization and Configuration
10 * + Data transfers functions
11 * + Hardware CRC Calculation
12 * + DMA transfers management
13 * + Interrupts and flags management
15 * @verbatim
18 ===============================================================================
19 ##### How to use this driver #####
20 ===============================================================================
21 [..]
22 (#) Enable peripheral clock using RCC_APBPeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE)
23 function for SPI1 or using RCC_APBPeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE)
24 function for SPI2.
25 (#) Enable SCK, MOSI, MISO and NSS GPIO clocks using RCC_AHBPeriphClockCmd()
26 function.
27 (#) Peripherals alternate function:
28 (++) Connect the pin to the desired peripherals' Alternate
29 Function (AF) using GPIO_PinAFConfig() function.
30 (++) Configure the desired pin in alternate function by:
31 GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF.
32 (++) Select the type, pull-up/pull-down and output speed via
33 GPIO_PuPd, GPIO_OType and GPIO_Speed members.
34 (++) Call GPIO_Init() function.
35 (#) Program the Polarity, Phase, First Data, Baud Rate Prescaler, Slave
36 Management, Peripheral Mode and CRC Polynomial values using the SPI_Init()
37 function in SPI mode. In I2S mode, program the Mode, Standard, Data Format,
38 MCLK Output, Audio frequency and Polarity using I2S_Init() function.
39 (#) Configure the FIFO threshold using SPI_RxFIFOThresholdConfig() to select
40 at which threshold the RXNE event is generated.
41 (#) Enable the NVIC and the corresponding interrupt using the function
42 SPI_I2S_ITConfig() if you need to use interrupt mode.
43 (#) When using the DMA mode
44 (++) Configure the DMA using DMA_Init() function.
45 (++) Active the needed channel Request using SPI_I2S_DMACmd() function.
46 (#) Enable the SPI using the SPI_Cmd() function or enable the I2S using
47 I2S_Cmd().
48 (#) Enable the DMA using the DMA_Cmd() function when using DMA mode.
49 (#) Optionally you can enable/configure the following parameters without
50 re-initialization (i.e there is no need to call again SPI_Init() function):
51 (++) When bidirectional mode (SPI_Direction_1Line_Rx or SPI_Direction_1Line_Tx)
52 is programmed as Data direction parameter using the SPI_Init() function
53 it can be possible to switch between SPI_Direction_Tx or SPI_Direction_Rx
54 using the SPI_BiDirectionalLineConfig() function.
55 (++) When SPI_NSS_Soft is selected as Slave Select Management parameter
56 using the SPI_Init() function it can be possible to manage the
57 NSS internal signal using the SPI_NSSInternalSoftwareConfig() function.
58 (++) Reconfigure the data size using the SPI_DataSizeConfig() function.
59 (++) Enable or disable the SS output using the SPI_SSOutputCmd() function.
60 (#) To use the CRC Hardware calculation feature refer to the Peripheral
61 CRC hardware Calculation subsection.
62 [..] It is possible to use SPI in I2S full duplex mode, in this case, each SPI
63 peripheral is able to manage sending and receiving data simultaneously
64 using two data lines. Each SPI peripheral has an extended block called I2Sxext
65 (ie. I2S2ext for SPI2 and I2S3ext for SPI3).
66 The extension block is not a full SPI IP, it is used only as I2S slave to
67 implement full duplex mode. The extension block uses the same clock sources
68 as its master.
69 To configure I2S full duplex you have to:
70 (#) Configure SPIx in I2S mode (I2S_Init() function) as described above.
71 (#) Call the I2S_FullDuplexConfig() function using the same strucutre passed to
72 I2S_Init() function.
73 (#) Call I2S_Cmd() for SPIx then for its extended block.
74 (#) Configure interrupts or DMA requests and to get/clear flag status,
75 use I2Sxext instance for the extension block.
76 [..] Functions that can be called with I2Sxext instances are:
77 I2S_Cmd(), I2S_FullDuplexConfig(), SPI_I2S_ReceiveData16(), SPI_I2S_SendData16(),
78 SPI_I2S_DMACmd(), SPI_I2S_ITConfig(), SPI_I2S_GetFlagStatus(), SPI_I2S_ClearFlag(),
79 SPI_I2S_GetITStatus() and SPI_I2S_ClearITPendingBit().
80 [..] Example: To use SPI3 in Full duplex mode (SPI3 is Master Tx, I2S3ext is Slave Rx):
81 [..] RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);
82 I2S_StructInit(&I2SInitStruct);
83 I2SInitStruct.Mode = I2S_Mode_MasterTx;
84 I2S_Init(SPI3, &I2SInitStruct);
85 I2S_FullDuplexConfig(SPI3ext, &I2SInitStruct)
86 I2S_Cmd(SPI3, ENABLE);
87 I2S_Cmd(SPI3ext, ENABLE);
88 ...
89 while (SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_TXE) == RESET)
91 SPI_I2S_SendData16(SPI3, txdata[i]);
92 ...
93 while (SPI_I2S_GetFlagStatus(I2S3ext, SPI_FLAG_RXNE) == RESET)
95 rxdata[i] = SPI_I2S_ReceiveData16(I2S3ext);
96 ...
97 [..]
98 (@) In SPI mode: To use the SPI TI mode, call the function SPI_TIModeCmd()
99 just after calling the function SPI_Init().
101 @endverbatim
102 ******************************************************************************
103 * @attention
105 * <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
107 * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
108 * You may not use this file except in compliance with the License.
109 * You may obtain a copy of the License at:
111 * http://www.st.com/software_license_agreement_liberty_v2
113 * Unless required by applicable law or agreed to in writing, software
114 * distributed under the License is distributed on an "AS IS" BASIS,
115 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
116 * See the License for the specific language governing permissions and
117 * limitations under the License.
119 ******************************************************************************
122 /* Includes ------------------------------------------------------------------*/
123 #include "stm32f30x_spi.h"
124 #include "stm32f30x_rcc.h"
126 /** @addtogroup STM32F30x_StdPeriph_Driver
127 * @{
130 /** @defgroup SPI
131 * @brief SPI driver modules
132 * @{
135 /* Private typedef -----------------------------------------------------------*/
136 /* Private define ------------------------------------------------------------*/
137 /* SPI registers Masks */
138 #define CR1_CLEAR_MASK ((uint16_t)0x3040)
139 #define CR2_LDMA_MASK ((uint16_t)0x9FFF)
141 #define I2SCFGR_CLEAR_MASK ((uint16_t)0xF040)
143 /* Private macro -------------------------------------------------------------*/
144 /* Private variables ---------------------------------------------------------*/
145 /* Private function prototypes -----------------------------------------------*/
146 /* Private functions ---------------------------------------------------------*/
148 /** @defgroup SPI_Private_Functions
149 * @{
152 /** @defgroup SPI_Group1 Initialization and Configuration functions
153 * @brief Initialization and Configuration functions
155 @verbatim
156 ===============================================================================
157 ##### Initialization and Configuration functions #####
158 ===============================================================================
159 [..] This section provides a set of functions allowing to initialize the SPI Direction,
160 SPI Mode, SPI Data Size, SPI Polarity, SPI Phase, SPI NSS Management, SPI Baud
161 Rate Prescaler, SPI First Bit and SPI CRC Polynomial.
162 [..] The SPI_Init() function follows the SPI configuration procedures for Master mode
163 and Slave mode (details for these procedures are available in reference manual).
164 [..] When the Software NSS management (SPI_InitStruct->SPI_NSS = SPI_NSS_Soft) is selected,
165 use the following function to manage the NSS bit:
166 void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft);
167 [..] In Master mode, when the Hardware NSS management (SPI_InitStruct->SPI_NSS = SPI_NSS_Hard)
168 is selected, use the follwoing function to enable the NSS output feature.
169 void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
170 [..] The NSS pulse mode can be managed by the SPI TI mode when enabling it using the
171 following function: void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
172 And it can be managed by software in the SPI Motorola mode using this function:
173 void SPI_NSSPulseModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
174 [..] This section provides also functions to initialize the I2S Mode, Standard,
175 Data Format, MCLK Output, Audio frequency and Polarity.
176 [..] The I2S_Init() function follows the I2S configuration procedures for Master mode
177 and Slave mode.
179 @endverbatim
180 * @{
184 * @brief Deinitializes the SPIx peripheral registers to their default
185 * reset values.
186 * @param SPIx: To select the SPIx peripheral, where x can be: 1, 2 or 3
187 * in SPI mode.
188 * @retval None
190 void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
192 /* Check the parameters */
193 assert_param(IS_SPI_ALL_PERIPH(SPIx));
195 if (SPIx == SPI1)
197 /* Enable SPI1 reset state */
198 RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
199 /* Release SPI1 from reset state */
200 RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
202 else if (SPIx == SPI2)
204 /* Enable SPI2 reset state */
205 RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
206 /* Release SPI2 from reset state */
207 RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
209 else
211 if (SPIx == SPI3)
213 /* Enable SPI3 reset state */
214 RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
215 /* Release SPI3 from reset state */
216 RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
222 * @brief Fills each SPI_InitStruct member with its default value.
223 * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure which will be initialized.
224 * @retval None
226 void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
228 /*--------------- Reset SPI init structure parameters values -----------------*/
229 /* Initialize the SPI_Direction member */
230 SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
231 /* Initialize the SPI_Mode member */
232 SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
233 /* Initialize the SPI_DataSize member */
234 SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
235 /* Initialize the SPI_CPOL member */
236 SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
237 /* Initialize the SPI_CPHA member */
238 SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
239 /* Initialize the SPI_NSS member */
240 SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
241 /* Initialize the SPI_BaudRatePrescaler member */
242 SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
243 /* Initialize the SPI_FirstBit member */
244 SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
245 /* Initialize the SPI_CRCPolynomial member */
246 SPI_InitStruct->SPI_CRCPolynomial = 7;
250 * @brief Initializes the SPIx peripheral according to the specified
251 * parameters in the SPI_InitStruct.
252 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
253 * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
254 * contains the configuration information for the specified SPI peripheral.
255 * @retval None
257 void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
259 uint16_t tmpreg = 0;
261 /* check the parameters */
262 assert_param(IS_SPI_ALL_PERIPH(SPIx));
264 /* Check the SPI parameters */
265 assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
266 assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
267 assert_param(IS_SPI_DATA_SIZE(SPI_InitStruct->SPI_DataSize));
268 assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
269 assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
270 assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
271 assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
272 assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
273 assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
275 /* Configuring the SPI in master mode */
276 if(SPI_InitStruct->SPI_Mode == SPI_Mode_Master)
278 /*---------------------------- SPIx CR1 Configuration ------------------------*/
279 /* Get the SPIx CR1 value */
280 tmpreg = SPIx->CR1;
281 /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
282 tmpreg &= CR1_CLEAR_MASK;
283 /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
284 master/slave mode, CPOL and CPHA */
285 /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
286 /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
287 /* Set LSBFirst bit according to SPI_FirstBit value */
288 /* Set BR bits according to SPI_BaudRatePrescaler value */
289 /* Set CPOL bit according to SPI_CPOL value */
290 /* Set CPHA bit according to SPI_CPHA value */
291 tmpreg |= (uint16_t)((uint16_t)(SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode) |
292 (uint16_t)((uint16_t)(SPI_InitStruct->SPI_CPOL | SPI_InitStruct->SPI_CPHA) |
293 (uint16_t)((uint16_t)(SPI_InitStruct->SPI_NSS | SPI_InitStruct->SPI_BaudRatePrescaler) |
294 SPI_InitStruct->SPI_FirstBit)));
295 /* Write to SPIx CR1 */
296 SPIx->CR1 = tmpreg;
297 /*-------------------------Data Size Configuration -----------------------*/
298 /* Get the SPIx CR2 value */
299 tmpreg = SPIx->CR2;
300 /* Clear DS[3:0] bits */
301 tmpreg &= (uint16_t)~SPI_CR2_DS;
302 /* Configure SPIx: Data Size */
303 tmpreg |= (uint16_t)(SPI_InitStruct->SPI_DataSize);
304 /* Write to SPIx CR2 */
305 SPIx->CR2 = tmpreg;
307 /* Configuring the SPI in slave mode */
308 else
310 /*---------------------------- Data size Configuration -----------------------*/
311 /* Get the SPIx CR2 value */
312 tmpreg = SPIx->CR2;
313 /* Clear DS[3:0] bits */
314 tmpreg &= (uint16_t)~SPI_CR2_DS;
315 /* Configure SPIx: Data Size */
316 tmpreg |= (uint16_t)(SPI_InitStruct->SPI_DataSize);
317 /* Write to SPIx CR2 */
318 SPIx->CR2 = tmpreg;
319 /*---------------------------- SPIx CR1 Configuration ------------------------*/
320 /* Get the SPIx CR1 value */
321 tmpreg = SPIx->CR1;
322 /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
323 tmpreg &= CR1_CLEAR_MASK;
324 /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
325 master/salve mode, CPOL and CPHA */
326 /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
327 /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
328 /* Set LSBFirst bit according to SPI_FirstBit value */
329 /* Set BR bits according to SPI_BaudRatePrescaler value */
330 /* Set CPOL bit according to SPI_CPOL value */
331 /* Set CPHA bit according to SPI_CPHA value */
332 tmpreg |= (uint16_t)((uint16_t)(SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode) |
333 (uint16_t)((uint16_t)(SPI_InitStruct->SPI_CPOL | SPI_InitStruct->SPI_CPHA) |
334 (uint16_t)((uint16_t)(SPI_InitStruct->SPI_NSS | SPI_InitStruct->SPI_BaudRatePrescaler) |
335 SPI_InitStruct->SPI_FirstBit)));
337 /* Write to SPIx CR1 */
338 SPIx->CR1 = tmpreg;
341 /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
342 SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SMOD);
344 /*---------------------------- SPIx CRCPOLY Configuration --------------------*/
345 /* Write to SPIx CRCPOLY */
346 SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
350 * @brief Fills each I2S_InitStruct member with its default value.
351 * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized.
352 * @retval None
354 void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
356 /*--------------- Reset I2S init structure parameters values -----------------*/
357 /* Initialize the I2S_Mode member */
358 I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
360 /* Initialize the I2S_Standard member */
361 I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
363 /* Initialize the I2S_DataFormat member */
364 I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
366 /* Initialize the I2S_MCLKOutput member */
367 I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
369 /* Initialize the I2S_AudioFreq member */
370 I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
372 /* Initialize the I2S_CPOL member */
373 I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
377 * @brief Initializes the SPIx peripheral according to the specified
378 * parameters in the I2S_InitStruct.
379 * @param SPIx:To select the SPIx peripheral, where x can be: 2 or 3
380 * in I2S mode.
381 * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
382 * contains the configuration information for the specified SPI peripheral
383 * configured in I2S mode.
384 * @note
385 * The function calculates the optimal prescaler needed to obtain the most
386 * accurate audio frequency (depending on the I2S clock source, the PLL values
387 * and the product configuration). But in case the prescaler value is greater
388 * than 511, the default value (0x02) will be configured instead.
389 * @retval None
391 void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
393 uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
394 uint32_t tmp = 0;
395 RCC_ClocksTypeDef RCC_Clocks;
396 uint32_t sourceclock = 0;
398 /* Check the I2S parameters */
399 assert_param(IS_SPI_23_PERIPH(SPIx));
400 assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
401 assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
402 assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
403 assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
404 assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
405 assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
407 /*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
408 /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
409 SPIx->I2SCFGR &= I2SCFGR_CLEAR_MASK;
410 SPIx->I2SPR = 0x0002;
412 /* Get the I2SCFGR register value */
413 tmpreg = SPIx->I2SCFGR;
415 /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
416 if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
418 i2sodd = (uint16_t)0;
419 i2sdiv = (uint16_t)2;
421 /* If the requested audio frequency is not the default, compute the prescaler */
422 else
424 /* Check the frame length (For the Prescaler computing) */
425 if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
427 /* Packet length is 16 bits */
428 packetlength = 1;
430 else
432 /* Packet length is 32 bits */
433 packetlength = 2;
436 /* I2S Clock source is System clock: Get System Clock frequency */
437 RCC_GetClocksFreq(&RCC_Clocks);
439 /* Get the source clock value: based on System Clock value */
440 sourceclock = RCC_Clocks.SYSCLK_Frequency;
442 /* Compute the Real divider depending on the MCLK output state with a floating point */
443 if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
445 /* MCLK output is enabled */
446 tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5);
448 else
450 /* MCLK output is disabled */
451 tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5);
454 /* Remove the floating point */
455 tmp = tmp / 10;
457 /* Check the parity of the divider */
458 i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
460 /* Compute the i2sdiv prescaler */
461 i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
463 /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
464 i2sodd = (uint16_t) (i2sodd << 8);
467 /* Test if the divider is 1 or 0 or greater than 0xFF */
468 if ((i2sdiv < 2) || (i2sdiv > 0xFF))
470 /* Set the default values */
471 i2sdiv = 2;
472 i2sodd = 0;
475 /* Write to SPIx I2SPR register the computed value */
476 SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput));
478 /* Configure the I2S with the SPI_InitStruct values */
479 tmpreg |= (uint16_t)((uint16_t)(SPI_I2SCFGR_I2SMOD | I2S_InitStruct->I2S_Mode) | \
480 (uint16_t)((uint16_t)((uint16_t)(I2S_InitStruct->I2S_Standard |I2S_InitStruct->I2S_DataFormat) |\
481 I2S_InitStruct->I2S_CPOL)));
483 /* Write to SPIx I2SCFGR */
484 SPIx->I2SCFGR = tmpreg;
488 * @brief Enables or disables the specified SPI peripheral.
489 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
490 * @param NewState: new state of the SPIx peripheral.
491 * This parameter can be: ENABLE or DISABLE.
492 * @retval None
494 void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
496 /* Check the parameters */
497 assert_param(IS_SPI_ALL_PERIPH(SPIx));
498 assert_param(IS_FUNCTIONAL_STATE(NewState));
500 if (NewState != DISABLE)
502 /* Enable the selected SPI peripheral */
503 SPIx->CR1 |= SPI_CR1_SPE;
505 else
507 /* Disable the selected SPI peripheral */
508 SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_SPE);
513 * @brief Enables or disables the TI Mode.
514 * @note This function can be called only after the SPI_Init() function has
515 * been called.
516 * @note When TI mode is selected, the control bits SSM, SSI, CPOL and CPHA
517 * are not taken into consideration and are configured by hardware
518 * respectively to the TI mode requirements.
519 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
520 * @param NewState: new state of the selected SPI TI communication mode.
521 * This parameter can be: ENABLE or DISABLE.
522 * @retval None
524 void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
526 /* Check the parameters */
527 assert_param(IS_SPI_ALL_PERIPH(SPIx));
528 assert_param(IS_FUNCTIONAL_STATE(NewState));
530 if (NewState != DISABLE)
532 /* Enable the TI mode for the selected SPI peripheral */
533 SPIx->CR2 |= SPI_CR2_FRF;
535 else
537 /* Disable the TI mode for the selected SPI peripheral */
538 SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_FRF);
543 * @brief Enables or disables the specified SPI peripheral (in I2S mode).
544 * @param SPIx:To select the SPIx peripheral, where x can be: 2 or 3 in
545 * I2S mode or I2Sxext for I2S full duplex mode.
546 * @param NewState: new state of the SPIx peripheral.
547 * This parameter can be: ENABLE or DISABLE.
548 * @retval None
550 void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
552 /* Check the parameters */
553 assert_param(IS_SPI_23_PERIPH_EXT(SPIx));
554 assert_param(IS_FUNCTIONAL_STATE(NewState));
555 if (NewState != DISABLE)
557 /* Enable the selected SPI peripheral in I2S mode */
558 SPIx->I2SCFGR |= SPI_I2SCFGR_I2SE;
560 else
562 /* Disable the selected SPI peripheral in I2S mode */
563 SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SE);
568 * @brief Configures the data size for the selected SPI.
569 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
570 * @param SPI_DataSize: specifies the SPI data size.
571 * For the SPIx peripheral this parameter can be one of the following values:
572 * @arg SPI_DataSize_4b: Set data size to 4 bits
573 * @arg SPI_DataSize_5b: Set data size to 5 bits
574 * @arg SPI_DataSize_6b: Set data size to 6 bits
575 * @arg SPI_DataSize_7b: Set data size to 7 bits
576 * @arg SPI_DataSize_8b: Set data size to 8 bits
577 * @arg SPI_DataSize_9b: Set data size to 9 bits
578 * @arg SPI_DataSize_10b: Set data size to 10 bits
579 * @arg SPI_DataSize_11b: Set data size to 11 bits
580 * @arg SPI_DataSize_12b: Set data size to 12 bits
581 * @arg SPI_DataSize_13b: Set data size to 13 bits
582 * @arg SPI_DataSize_14b: Set data size to 14 bits
583 * @arg SPI_DataSize_15b: Set data size to 15 bits
584 * @arg SPI_DataSize_16b: Set data size to 16 bits
585 * @retval None
587 void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize)
589 uint16_t tmpreg = 0;
591 /* Check the parameters */
592 assert_param(IS_SPI_ALL_PERIPH(SPIx));
593 assert_param(IS_SPI_DATA_SIZE(SPI_DataSize));
594 /* Read the CR2 register */
595 tmpreg = SPIx->CR2;
596 /* Clear DS[3:0] bits */
597 tmpreg &= (uint16_t)~SPI_CR2_DS;
598 /* Set new DS[3:0] bits value */
599 tmpreg |= SPI_DataSize;
600 SPIx->CR2 = tmpreg;
604 * @brief Configures the FIFO reception threshold for the selected SPI.
605 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
606 * @param SPI_RxFIFOThreshold: specifies the FIFO reception threshold.
607 * This parameter can be one of the following values:
608 * @arg SPI_RxFIFOThreshold_HF: RXNE event is generated if the FIFO
609 * level is greater or equal to 1/2.
610 * @arg SPI_RxFIFOThreshold_QF: RXNE event is generated if the FIFO
611 * level is greater or equal to 1/4.
612 * @retval None
614 void SPI_RxFIFOThresholdConfig(SPI_TypeDef* SPIx, uint16_t SPI_RxFIFOThreshold)
616 /* Check the parameters */
617 assert_param(IS_SPI_ALL_PERIPH(SPIx));
618 assert_param(IS_SPI_RX_FIFO_THRESHOLD(SPI_RxFIFOThreshold));
620 /* Clear FRXTH bit */
621 SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_FRXTH);
623 /* Set new FRXTH bit value */
624 SPIx->CR2 |= SPI_RxFIFOThreshold;
628 * @brief Selects the data transfer direction in bidirectional mode for the specified SPI.
629 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
630 * @param SPI_Direction: specifies the data transfer direction in bidirectional mode.
631 * This parameter can be one of the following values:
632 * @arg SPI_Direction_Tx: Selects Tx transmission direction
633 * @arg SPI_Direction_Rx: Selects Rx receive direction
634 * @retval None
636 void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction)
638 /* Check the parameters */
639 assert_param(IS_SPI_ALL_PERIPH(SPIx));
640 assert_param(IS_SPI_DIRECTION(SPI_Direction));
641 if (SPI_Direction == SPI_Direction_Tx)
643 /* Set the Tx only mode */
644 SPIx->CR1 |= SPI_Direction_Tx;
646 else
648 /* Set the Rx only mode */
649 SPIx->CR1 &= SPI_Direction_Rx;
654 * @brief Configures internally by software the NSS pin for the selected SPI.
655 * @note This function can be called only after the SPI_Init() function has
656 * been called.
657 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
658 * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state.
659 * This parameter can be one of the following values:
660 * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally
661 * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally
662 * @retval None
664 void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft)
666 /* Check the parameters */
667 assert_param(IS_SPI_ALL_PERIPH(SPIx));
668 assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
670 if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
672 /* Set NSS pin internally by software */
673 SPIx->CR1 |= SPI_NSSInternalSoft_Set;
675 else
677 /* Reset NSS pin internally by software */
678 SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
683 * @brief Configures the full duplex mode for the I2Sx peripheral using its
684 * extension I2Sxext according to the specified parameters in the
685 * I2S_InitStruct.
686 * @param I2Sxext: where x can be 2 or 3 to select the I2S peripheral extension block.
687 * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
688 * contains the configuration information for the specified I2S peripheral
689 * extension.
691 * @note The structure pointed by I2S_InitStruct parameter should be the same
692 * used for the master I2S peripheral. In this case, if the master is
693 * configured as transmitter, the slave will be receiver and vice versa.
694 * Or you can force a different mode by modifying the field I2S_Mode to the
695 * value I2S_SlaveRx or I2S_SlaveTx indepedently of the master configuration.
697 * @note The I2S full duplex extension can be configured in slave mode only.
699 * @retval None
701 void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct)
703 uint16_t tmpreg = 0, tmp = 0;
705 /* Check the I2S parameters */
706 assert_param(IS_I2S_EXT_PERIPH(I2Sxext));
707 assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
708 assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
709 assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
710 assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));
712 /*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
713 /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
714 I2Sxext->I2SCFGR &= I2SCFGR_CLEAR_MASK;
715 I2Sxext->I2SPR = 0x0002;
717 /* Get the I2SCFGR register value */
718 tmpreg = I2Sxext->I2SCFGR;
720 /* Get the mode to be configured for the extended I2S */
721 if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterTx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveTx))
723 tmp = I2S_Mode_SlaveRx;
725 else
727 if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterRx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveRx))
729 tmp = I2S_Mode_SlaveTx;
734 /* Configure the I2S with the SPI_InitStruct values */
735 tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(tmp | \
736 (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
737 (uint16_t)I2S_InitStruct->I2S_CPOL))));
739 /* Write to SPIx I2SCFGR */
740 I2Sxext->I2SCFGR = tmpreg;
744 * @brief Enables or disables the SS output for the selected SPI.
745 * @note This function can be called only after the SPI_Init() function has
746 * been called and the NSS hardware management mode is selected.
747 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
748 * @param NewState: new state of the SPIx SS output.
749 * This parameter can be: ENABLE or DISABLE.
750 * @retval None
752 void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
754 /* Check the parameters */
755 assert_param(IS_SPI_ALL_PERIPH(SPIx));
756 assert_param(IS_FUNCTIONAL_STATE(NewState));
757 if (NewState != DISABLE)
759 /* Enable the selected SPI SS output */
760 SPIx->CR2 |= (uint16_t)SPI_CR2_SSOE;
762 else
764 /* Disable the selected SPI SS output */
765 SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_SSOE);
770 * @brief Enables or disables the NSS pulse management mode.
771 * @note This function can be called only after the SPI_Init() function has
772 * been called.
773 * @note When TI mode is selected, the control bits NSSP is not taken into
774 * consideration and are configured by hardware respectively to the
775 * TI mode requirements.
776 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
777 * @param NewState: new state of the NSS pulse management mode.
778 * This parameter can be: ENABLE or DISABLE.
779 * @retval None
781 void SPI_NSSPulseModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
783 /* Check the parameters */
784 assert_param(IS_SPI_ALL_PERIPH(SPIx));
785 assert_param(IS_FUNCTIONAL_STATE(NewState));
787 if (NewState != DISABLE)
789 /* Enable the NSS pulse management mode */
790 SPIx->CR2 |= SPI_CR2_NSSP;
792 else
794 /* Disable the NSS pulse management mode */
795 SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_NSSP);
800 * @}
803 /** @defgroup SPI_Group2 Data transfers functions
804 * @brief Data transfers functions
806 @verbatim
807 ===============================================================================
808 ##### Data transfers functions #####
809 ===============================================================================
810 [..] This section provides a set of functions allowing to manage the SPI or I2S
811 data transfers.
812 [..] In reception, data are received and then stored into an internal Rx buffer while
813 In transmission, data are first stored into an internal Tx buffer before being
814 transmitted.
815 [..] The read access of the SPI_DR register can be done using the SPI_I2S_ReceiveData()
816 function and returns the Rx buffered value. Whereas a write access to the SPI_DR
817 can be done using SPI_I2S_SendData() function and stores the written data into
818 Tx buffer.
820 @endverbatim
821 * @{
825 * @brief Transmits a Data through the SPIx peripheral.
826 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
827 * @param Data: Data to be transmitted.
828 * @retval None
830 void SPI_SendData8(SPI_TypeDef* SPIx, uint8_t Data)
832 uint32_t spixbase = 0x00;
834 /* Check the parameters */
835 assert_param(IS_SPI_ALL_PERIPH(SPIx));
837 spixbase = (uint32_t)SPIx;
838 spixbase += 0x0C;
840 *(__IO uint8_t *) spixbase = Data;
844 * @brief Transmits a Data through the SPIx/I2Sx peripheral.
845 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
846 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
847 * @param Data: Data to be transmitted.
848 * @retval None
850 void SPI_I2S_SendData16(SPI_TypeDef* SPIx, uint16_t Data)
852 /* Check the parameters */
853 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
855 SPIx->DR = (uint16_t)Data;
859 * @brief Returns the most recent received data by the SPIx peripheral.
860 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
861 * @retval The value of the received data.
863 uint8_t SPI_ReceiveData8(SPI_TypeDef* SPIx)
865 uint32_t spixbase = 0x00;
867 /* Check the parameters */
868 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
870 spixbase = (uint32_t)SPIx;
871 spixbase += 0x0C;
873 return *(__IO uint8_t *) spixbase;
877 * @brief Returns the most recent received data by the SPIx peripheral.
878 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
879 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
880 * @retval The value of the received data.
882 uint16_t SPI_I2S_ReceiveData16(SPI_TypeDef* SPIx)
884 /* Check the parameters */
885 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
887 return SPIx->DR;
890 * @}
893 /** @defgroup SPI_Group3 Hardware CRC Calculation functions
894 * @brief Hardware CRC Calculation functions
896 @verbatim
897 ===============================================================================
898 ##### Hardware CRC Calculation functions #####
899 ===============================================================================
900 [..] This section provides a set of functions allowing to manage the SPI CRC hardware
901 calculation.
902 [..] SPI communication using CRC is possible through the following procedure:
903 (#) Program the Data direction, Polarity, Phase, First Data, Baud Rate Prescaler,
904 Slave Management, Peripheral Mode and CRC Polynomial values using the SPI_Init()
905 function.
906 (#) Enable the CRC calculation using the SPI_CalculateCRC() function.
907 (#) Enable the SPI using the SPI_Cmd() function
908 (#) Before writing the last data to the TX buffer, set the CRCNext bit using the
909 SPI_TransmitCRC() function to indicate that after transmission of the last
910 data, the CRC should be transmitted.
911 (#) After transmitting the last data, the SPI transmits the CRC. The SPI_CR1_CRCNEXT
912 bit is reset. The CRC is also received and compared against the SPI_RXCRCR
913 value.
914 If the value does not match, the SPI_FLAG_CRCERR flag is set and an interrupt
915 can be generated when the SPI_I2S_IT_ERR interrupt is enabled.
916 [..]
918 (+@) It is advised to don't read the calculate CRC values during the communication.
919 (+@) When the SPI is in slave mode, be careful to enable CRC calculation only
920 when the clock is stable, that is, when the clock is in the steady state.
921 If not, a wrong CRC calculation may be done. In fact, the CRC is sensitive
922 to the SCK slave input clock as soon as CRCEN is set, and this, whatever
923 the value of the SPE bit.
924 (+@) With high bitrate frequencies, be careful when transmitting the CRC.
925 As the number of used CPU cycles has to be as low as possible in the CRC
926 transfer phase, it is forbidden to call software functions in the CRC
927 transmission sequence to avoid errors in the last data and CRC reception.
928 In fact, CRCNEXT bit has to be written before the end of the transmission/reception
929 of the last data.
930 (+@) For high bit rate frequencies, it is advised to use the DMA mode to avoid the
931 degradation of the SPI speed performance due to CPU accesses impacting the
932 SPI bandwidth.
933 (+@) When the STM32F30x are configured as slaves and the NSS hardware mode is
934 used, the NSS pin needs to be kept low between the data phase and the CRC
935 phase.
936 (+@) When the SPI is configured in slave mode with the CRC feature enabled, CRC
937 calculation takes place even if a high level is applied on the NSS pin.
938 This may happen for example in case of a multislave environment where the
939 communication master addresses slaves alternately.
940 (+@) Between a slave deselection (high level on NSS) and a new slave selection
941 (low level on NSS), the CRC value should be cleared on both master and slave
942 sides in order to resynchronize the master and slave for their respective
943 CRC calculation.
944 [..]
945 (@) To clear the CRC, follow the procedure below:
946 (#@) Disable SPI using the SPI_Cmd() function.
947 (#@) Disable the CRC calculation using the SPI_CalculateCRC() function.
948 (#@) Enable the CRC calculation using the SPI_CalculateCRC() function.
949 (#@) Enable SPI using the SPI_Cmd() function.
951 @endverbatim
952 * @{
956 * @brief Configures the CRC calculation length for the selected SPI.
957 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
958 * @param SPI_CRCLength: specifies the SPI CRC calculation length.
959 * This parameter can be one of the following values:
960 * @arg SPI_CRCLength_8b: Set CRC Calculation to 8 bits
961 * @arg SPI_CRCLength_16b: Set CRC Calculation to 16 bits
962 * @retval None
964 void SPI_CRCLengthConfig(SPI_TypeDef* SPIx, uint16_t SPI_CRCLength)
966 /* Check the parameters */
967 assert_param(IS_SPI_ALL_PERIPH(SPIx));
968 assert_param(IS_SPI_CRC_LENGTH(SPI_CRCLength));
970 /* Clear CRCL bit */
971 SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCL);
973 /* Set new CRCL bit value */
974 SPIx->CR1 |= SPI_CRCLength;
978 * @brief Enables or disables the CRC value calculation of the transferred bytes.
979 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
980 * @param NewState: new state of the SPIx CRC value calculation.
981 * This parameter can be: ENABLE or DISABLE.
982 * @retval None
984 void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
986 /* Check the parameters */
987 assert_param(IS_SPI_ALL_PERIPH(SPIx));
988 assert_param(IS_FUNCTIONAL_STATE(NewState));
990 if (NewState != DISABLE)
992 /* Enable the selected SPI CRC calculation */
993 SPIx->CR1 |= SPI_CR1_CRCEN;
995 else
997 /* Disable the selected SPI CRC calculation */
998 SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCEN);
1003 * @brief Transmits the SPIx CRC value.
1004 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1005 * @retval None
1007 void SPI_TransmitCRC(SPI_TypeDef* SPIx)
1009 /* Check the parameters */
1010 assert_param(IS_SPI_ALL_PERIPH(SPIx));
1012 /* Enable the selected SPI CRC transmission */
1013 SPIx->CR1 |= SPI_CR1_CRCNEXT;
1017 * @brief Returns the transmit or the receive CRC register value for the specified SPI.
1018 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1019 * @param SPI_CRC: specifies the CRC register to be read.
1020 * This parameter can be one of the following values:
1021 * @arg SPI_CRC_Tx: Selects Tx CRC register
1022 * @arg SPI_CRC_Rx: Selects Rx CRC register
1023 * @retval The selected CRC register value..
1025 uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC)
1027 uint16_t crcreg = 0;
1028 /* Check the parameters */
1029 assert_param(IS_SPI_ALL_PERIPH(SPIx));
1030 assert_param(IS_SPI_CRC(SPI_CRC));
1032 if (SPI_CRC != SPI_CRC_Rx)
1034 /* Get the Tx CRC register */
1035 crcreg = SPIx->TXCRCR;
1037 else
1039 /* Get the Rx CRC register */
1040 crcreg = SPIx->RXCRCR;
1042 /* Return the selected CRC register */
1043 return crcreg;
1047 * @brief Returns the CRC Polynomial register value for the specified SPI.
1048 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1049 * @retval The CRC Polynomial register value.
1051 uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
1053 /* Check the parameters */
1054 assert_param(IS_SPI_ALL_PERIPH(SPIx));
1056 /* Return the CRC polynomial register */
1057 return SPIx->CRCPR;
1061 * @}
1064 /** @defgroup SPI_Group4 DMA transfers management functions
1065 * @brief DMA transfers management functions
1067 @verbatim
1068 ===============================================================================
1069 ##### DMA transfers management functions #####
1070 ===============================================================================
1072 @endverbatim
1073 * @{
1077 * @brief Enables or disables the SPIx/I2Sx DMA interface.
1078 * @param SPIx:To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
1079 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
1080 * @param SPI_I2S_DMAReq: specifies the SPI DMA transfer request to be enabled or disabled.
1081 * This parameter can be any combination of the following values:
1082 * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
1083 * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
1084 * @param NewState: new state of the selected SPI DMA transfer request.
1085 * This parameter can be: ENABLE or DISABLE.
1086 * @retval None
1088 void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
1090 /* Check the parameters */
1091 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
1092 assert_param(IS_FUNCTIONAL_STATE(NewState));
1093 assert_param(IS_SPI_I2S_DMA_REQ(SPI_I2S_DMAReq));
1095 if (NewState != DISABLE)
1097 /* Enable the selected SPI DMA requests */
1098 SPIx->CR2 |= SPI_I2S_DMAReq;
1100 else
1102 /* Disable the selected SPI DMA requests */
1103 SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq;
1108 * @brief Configures the number of data to transfer type(Even/Odd) for the DMA
1109 * last transfers and for the selected SPI.
1110 * @note This function have a meaning only if DMA mode is selected and if
1111 * the packing mode is used (data length <= 8 and DMA transfer size halfword)
1112 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1113 * @param SPI_LastDMATransfer: specifies the SPI last DMA transfers state.
1114 * This parameter can be one of the following values:
1115 * @arg SPI_LastDMATransfer_TxEvenRxEven: Number of data for transmission Even
1116 * and number of data for reception Even.
1117 * @arg SPI_LastDMATransfer_TxOddRxEven: Number of data for transmission Odd
1118 * and number of data for reception Even.
1119 * @arg SPI_LastDMATransfer_TxEvenRxOdd: Number of data for transmission Even
1120 * and number of data for reception Odd.
1121 * @arg SPI_LastDMATransfer_TxOddRxOdd: RNumber of data for transmission Odd
1122 * and number of data for reception Odd.
1123 * @retval None
1125 void SPI_LastDMATransferCmd(SPI_TypeDef* SPIx, uint16_t SPI_LastDMATransfer)
1127 /* Check the parameters */
1128 assert_param(IS_SPI_ALL_PERIPH(SPIx));
1129 assert_param(IS_SPI_LAST_DMA_TRANSFER(SPI_LastDMATransfer));
1131 /* Clear LDMA_TX and LDMA_RX bits */
1132 SPIx->CR2 &= CR2_LDMA_MASK;
1134 /* Set new LDMA_TX and LDMA_RX bits value */
1135 SPIx->CR2 |= SPI_LastDMATransfer;
1139 * @}
1142 /** @defgroup SPI_Group5 Interrupts and flags management functions
1143 * @brief Interrupts and flags management functions
1145 @verbatim
1146 ===============================================================================
1147 ##### Interrupts and flags management functions #####
1148 ===============================================================================
1149 [..] This section provides a set of functions allowing to configure the SPI/I2S
1150 Interrupts sources and check or clear the flags or pending bits status.
1151 The user should identify which mode will be used in his application to manage
1152 the communication: Polling mode, Interrupt mode or DMA mode.
1154 *** Polling Mode ***
1155 ====================
1156 [..] In Polling Mode, the SPI/I2S communication can be managed by 9 flags:
1157 (#) SPI_I2S_FLAG_TXE : to indicate the status of the transmit buffer register.
1158 (#) SPI_I2S_FLAG_RXNE : to indicate the status of the receive buffer register.
1159 (#) SPI_I2S_FLAG_BSY : to indicate the state of the communication layer of the SPI.
1160 (#) SPI_FLAG_CRCERR : to indicate if a CRC Calculation error occur.
1161 (#) SPI_FLAG_MODF : to indicate if a Mode Fault error occur.
1162 (#) SPI_I2S_FLAG_OVR : to indicate if an Overrun error occur.
1163 (#) SPI_I2S_FLAG_FRE: to indicate a Frame Format error occurs.
1164 (#) I2S_FLAG_UDR: to indicate an Underrun error occurs.
1165 (#) I2S_FLAG_CHSIDE: to indicate Channel Side.
1166 [..]
1167 (@) Do not use the BSY flag to handle each data transmission or reception.
1168 It is better to use the TXE and RXNE flags instead.
1169 [..] In this Mode it is advised to use the following functions:
1170 (+) FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
1171 (+) void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
1173 *** Interrupt Mode ***
1174 ======================
1175 [..] In Interrupt Mode, the SPI/I2S communication can be managed by 3 interrupt sources
1176 and 5 pending bits:
1177 [..] Pending Bits:
1178 (#) SPI_I2S_IT_TXE : to indicate the status of the transmit buffer register.
1179 (#) SPI_I2S_IT_RXNE : to indicate the status of the receive buffer register.
1180 (#) SPI_I2S_IT_OVR : to indicate if an Overrun error occur.
1181 (#) I2S_IT_UDR : to indicate an Underrun Error occurs.
1182 (#) SPI_I2S_FLAG_FRE : to indicate a Frame Format error occurs.
1183 [..] Interrupt Source:
1184 (#) SPI_I2S_IT_TXE: specifies the interrupt source for the Tx buffer empty
1185 interrupt.
1186 (#) SPI_I2S_IT_RXNE : specifies the interrupt source for the Rx buffer not
1187 empty interrupt.
1188 (#) SPI_I2S_IT_ERR : specifies the interrupt source for the errors interrupt.
1189 [..] In this Mode it is advised to use the following functions:
1190 (+) void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
1191 (+) ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
1193 *** FIFO Status ***
1194 ===================
1195 [..] It is possible to monitor the FIFO status when a transfer is ongoing using the
1196 following function:
1197 (+) uint32_t SPI_GetFIFOStatus(uint8_t SPI_FIFO_Direction);
1199 *** DMA Mode ***
1200 ================
1201 [..] In DMA Mode, the SPI communication can be managed by 2 DMA Channel requests:
1202 (#) SPI_I2S_DMAReq_Tx: specifies the Tx buffer DMA transfer request.
1203 (#) SPI_I2S_DMAReq_Rx: specifies the Rx buffer DMA transfer request.
1204 [..] In this Mode it is advised to use the following function:
1205 (+) void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState);
1207 @endverbatim
1208 * @{
1212 * @brief Enables or disables the specified SPI/I2S interrupts.
1213 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
1214 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
1215 * @param SPI_I2S_IT: specifies the SPI interrupt source to be enabled or disabled.
1216 * This parameter can be one of the following values:
1217 * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
1218 * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
1219 * @arg SPI_I2S_IT_ERR: Error interrupt mask
1220 * @param NewState: new state of the specified SPI interrupt.
1221 * This parameter can be: ENABLE or DISABLE.
1222 * @retval None
1224 void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
1226 uint16_t itpos = 0, itmask = 0 ;
1228 /* Check the parameters */
1229 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
1230 assert_param(IS_FUNCTIONAL_STATE(NewState));
1231 assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
1233 /* Get the SPI IT index */
1234 itpos = SPI_I2S_IT >> 4;
1236 /* Set the IT mask */
1237 itmask = (uint16_t)1 << (uint16_t)itpos;
1239 if (NewState != DISABLE)
1241 /* Enable the selected SPI interrupt */
1242 SPIx->CR2 |= itmask;
1244 else
1246 /* Disable the selected SPI interrupt */
1247 SPIx->CR2 &= (uint16_t)~itmask;
1252 * @brief Returns the current SPIx Transmission FIFO filled level.
1253 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1254 * @retval The Transmission FIFO filling state.
1255 * - SPI_TransmissionFIFOStatus_Empty: when FIFO is empty
1256 * - SPI_TransmissionFIFOStatus_1QuarterFull: if more than 1 quarter-full.
1257 * - SPI_TransmissionFIFOStatus_HalfFull: if more than 1 half-full.
1258 * - SPI_TransmissionFIFOStatus_Full: when FIFO is full.
1260 uint16_t SPI_GetTransmissionFIFOStatus(SPI_TypeDef* SPIx)
1262 /* Get the SPIx Transmission FIFO level bits */
1263 return (uint16_t)((SPIx->SR & SPI_SR_FTLVL));
1267 * @brief Returns the current SPIx Reception FIFO filled level.
1268 * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
1269 * @retval The Reception FIFO filling state.
1270 * - SPI_ReceptionFIFOStatus_Empty: when FIFO is empty
1271 * - SPI_ReceptionFIFOStatus_1QuarterFull: if more than 1 quarter-full.
1272 * - SPI_ReceptionFIFOStatus_HalfFull: if more than 1 half-full.
1273 * - SPI_ReceptionFIFOStatus_Full: when FIFO is full.
1275 uint16_t SPI_GetReceptionFIFOStatus(SPI_TypeDef* SPIx)
1277 /* Get the SPIx Reception FIFO level bits */
1278 return (uint16_t)((SPIx->SR & SPI_SR_FRLVL));
1282 * @brief Checks whether the specified SPI flag is set or not.
1283 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
1284 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
1285 * @param SPI_I2S_FLAG: specifies the SPI flag to check.
1286 * This parameter can be one of the following values:
1287 * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
1288 * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
1289 * @arg SPI_I2S_FLAG_BSY: Busy flag.
1290 * @arg SPI_I2S_FLAG_OVR: Overrun flag.
1291 * @arg SPI_I2S_FLAG_MODF: Mode Fault flag.
1292 * @arg SPI_I2S_FLAG_CRCERR: CRC Error flag.
1293 * @arg SPI_I2S_FLAG_FRE: TI frame format error flag.
1294 * @arg I2S_FLAG_UDR: Underrun Error flag.
1295 * @arg I2S_FLAG_CHSIDE: Channel Side flag.
1296 * @retval The new state of SPI_I2S_FLAG (SET or RESET).
1298 FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
1300 FlagStatus bitstatus = RESET;
1301 /* Check the parameters */
1302 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
1303 assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
1305 /* Check the status of the specified SPI flag */
1306 if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET)
1308 /* SPI_I2S_FLAG is set */
1309 bitstatus = SET;
1311 else
1313 /* SPI_I2S_FLAG is reset */
1314 bitstatus = RESET;
1316 /* Return the SPI_I2S_FLAG status */
1317 return bitstatus;
1321 * @brief Clears the SPIx CRC Error (CRCERR) flag.
1322 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
1323 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
1324 * @param SPI_I2S_FLAG: specifies the SPI flag to clear.
1325 * This function clears only CRCERR flag.
1326 * @note OVR (OverRun error) flag is cleared by software sequence: a read
1327 * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read
1328 * operation to SPI_SR register (SPI_I2S_GetFlagStatus()).
1329 * @note MODF (Mode Fault) flag is cleared by software sequence: a read/write
1330 * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a
1331 * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI).
1332 * @retval None
1334 void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
1336 /* Check the parameters */
1337 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
1338 assert_param(IS_SPI_CLEAR_FLAG(SPI_I2S_FLAG));
1340 /* Clear the selected SPI CRC Error (CRCERR) flag */
1341 SPIx->SR = (uint16_t)~SPI_I2S_FLAG;
1345 * @brief Checks whether the specified SPI/I2S interrupt has occurred or not.
1346 * @param SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2 or 3
1347 * in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.
1348 * @param SPI_I2S_IT: specifies the SPI interrupt source to check.
1349 * This parameter can be one of the following values:
1350 * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
1351 * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
1352 * @arg SPI_IT_MODF: Mode Fault interrupt.
1353 * @arg SPI_I2S_IT_OVR: Overrun interrupt.
1354 * @arg I2S_IT_UDR: Underrun interrupt.
1355 * @arg SPI_I2S_IT_FRE: Format Error interrupt.
1356 * @retval The new state of SPI_I2S_IT (SET or RESET).
1358 ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
1360 ITStatus bitstatus = RESET;
1361 uint16_t itpos = 0, itmask = 0, enablestatus = 0;
1363 /* Check the parameters */
1364 assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
1365 assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
1367 /* Get the SPI_I2S_IT index */
1368 itpos = 0x01 << (SPI_I2S_IT & 0x0F);
1370 /* Get the SPI_I2S_IT IT mask */
1371 itmask = SPI_I2S_IT >> 4;
1373 /* Set the IT mask */
1374 itmask = 0x01 << itmask;
1376 /* Get the SPI_I2S_IT enable bit status */
1377 enablestatus = (SPIx->CR2 & itmask) ;
1379 /* Check the status of the specified SPI interrupt */
1380 if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus)
1382 /* SPI_I2S_IT is set */
1383 bitstatus = SET;
1385 else
1387 /* SPI_I2S_IT is reset */
1388 bitstatus = RESET;
1390 /* Return the SPI_I2S_IT status */
1391 return bitstatus;
1395 * @}
1399 * @}
1403 * @}
1407 * @}
1410 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/