Merge pull request #10558 from iNavFlight/MrD_Correct-comments-on-OSD-symbols
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_spi.c
blobe86849003338be469fdbb72a4bb9e6993cabc7cd
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_spi.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief SPI HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Serial Peripheral Interface (SPI) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
15 @verbatim
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
19 [..]
20 The SPI HAL driver can be used as follows:
22 (#) Declare a SPI_HandleTypeDef handle structure, for example:
23 SPI_HandleTypeDef hspi;
25 (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API:
26 (##) Enable the SPIx interface clock
27 (##) SPI pins configuration
28 (+++) Enable the clock for the SPI GPIOs
29 (+++) Configure these SPI pins as alternate function push-pull
30 (##) NVIC configuration if you need to use interrupt process
31 (+++) Configure the SPIx interrupt priority
32 (+++) Enable the NVIC SPI IRQ handle
33 (##) DMA Configuration if you need to use DMA process
34 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel
35 (+++) Enable the DMAx clock
36 (+++) Configure the DMA handle parameters
37 (+++) Configure the DMA Tx or Rx Stream/Channel
38 (+++) Associate the initialized hdma_tx handle to the hspi DMA Tx or Rx handle
39 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel
41 (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS
42 management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure.
44 (#) Initialize the SPI registers by calling the HAL_SPI_Init() API:
45 (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
46 by calling the customized HAL_SPI_MspInit() API.
47 [..]
48 Circular mode restriction:
49 (#) The DMA circular mode cannot be used when the SPI is configured in these modes:
50 (##) Master 2Lines RxOnly
51 (##) Master 1Line Rx
52 (#) The CRC feature is not managed when the DMA circular mode is enabled
53 (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs
54 the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks
56 [..]
57 (@) The max SPI frequency depend on SPI data size (4bits, 5bits,..., 8bits,...15bits, 16bits),
58 SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA).
59 (@)
60 (+@) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA()
61 (+@) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA()
62 (+@) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA()
64 @endverbatim
66 Using the HAL it is not possible to reach all supported SPI frequency with the differents SPI Modes,
67 the following table resume the max SPI frequency reached with data size 8bits/16bits,
68 according to frequency used on APBx Peripheral Clock (fPCLK) used by the SPI instance :
70 DataSize = SPI_DATASIZE_8BIT:
71 +----------------------------------------------------------------------------------------------+
72 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
73 | Process | Tranfert mode |---------------------|----------------------|----------------------|
74 | | | Master | Slave | Master | Slave | Master | Slave |
75 |==============================================================================================|
76 | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
77 | X |----------------|----------|----------|-----------|----------|-----------|----------|
78 | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
79 | R |----------------|----------|----------|-----------|----------|-----------|----------|
80 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
81 |=========|================|==========|==========|===========|==========|===========|==========|
82 | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
83 | |----------------|----------|----------|-----------|----------|-----------|----------|
84 | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
85 | X |----------------|----------|----------|-----------|----------|-----------|----------|
86 | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
87 |=========|================|==========|==========|===========|==========|===========|==========|
88 | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
89 | |----------------|----------|----------|-----------|----------|-----------|----------|
90 | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
91 | X |----------------|----------|----------|-----------|----------|-----------|----------|
92 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
93 +----------------------------------------------------------------------------------------------+
95 DataSize = SPI_DATASIZE_16BIT:
96 +----------------------------------------------------------------------------------------------+
97 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
98 | Process | Tranfert mode |---------------------|----------------------|----------------------|
99 | | | Master | Slave | Master | Slave | Master | Slave |
100 |==============================================================================================|
101 | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
102 | X |----------------|----------|----------|-----------|----------|-----------|----------|
103 | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
104 | R |----------------|----------|----------|-----------|----------|-----------|----------|
105 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
106 |=========|================|==========|==========|===========|==========|===========|==========|
107 | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
108 | |----------------|----------|----------|-----------|----------|-----------|----------|
109 | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
110 | X |----------------|----------|----------|-----------|----------|-----------|----------|
111 | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
112 |=========|================|==========|==========|===========|==========|===========|==========|
113 | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
114 | |----------------|----------|----------|-----------|----------|-----------|----------|
115 | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
116 | X |----------------|----------|----------|-----------|----------|-----------|----------|
117 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
118 +----------------------------------------------------------------------------------------------+
120 ******************************************************************************
121 * @attention
123 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
125 * Redistribution and use in source and binary forms, with or without modification,
126 * are permitted provided that the following conditions are met:
127 * 1. Redistributions of source code must retain the above copyright notice,
128 * this list of conditions and the following disclaimer.
129 * 2. Redistributions in binary form must reproduce the above copyright notice,
130 * this list of conditions and the following disclaimer in the documentation
131 * and/or other materials provided with the distribution.
132 * 3. Neither the name of STMicroelectronics nor the names of its contributors
133 * may be used to endorse or promote products derived from this software
134 * without specific prior written permission.
136 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
137 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
138 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
139 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
140 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
141 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
142 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
143 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
144 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
145 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
147 ******************************************************************************
150 /* Includes ------------------------------------------------------------------*/
151 #include "stm32f7xx_hal.h"
153 /** @addtogroup STM32F7xx_HAL_Driver
154 * @{
157 /** @defgroup SPI SPI
158 * @brief SPI HAL module driver
159 * @{
161 #ifdef HAL_SPI_MODULE_ENABLED
163 /* Private typedef -----------------------------------------------------------*/
164 /* Private defines -----------------------------------------------------------*/
165 /** @defgroup SPI_Private_Constants SPI Private Constants
166 * @{
168 #define SPI_DEFAULT_TIMEOUT 100U
170 * @}
173 /* Private macros ------------------------------------------------------------*/
174 /* Private variables ---------------------------------------------------------*/
175 /* Private function prototypes -----------------------------------------------*/
176 /** @defgroup SPI_Private_Functions SPI Private Functions
177 * @{
179 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma);
180 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
181 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma);
182 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma);
183 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma);
184 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma);
185 static void SPI_DMAError(DMA_HandleTypeDef *hdma);
186 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma);
187 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
188 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
189 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State,
190 uint32_t Timeout, uint32_t Tickstart);
191 static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
192 uint32_t Timeout, uint32_t Tickstart);
193 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
194 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
195 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
196 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
197 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
198 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
199 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
200 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
201 #if (USE_SPI_CRC != 0U)
202 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
203 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
204 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
205 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
206 #endif /* USE_SPI_CRC */
207 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi);
208 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi);
209 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi);
210 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi);
211 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi);
212 static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
213 static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
215 * @}
218 /* Exported functions --------------------------------------------------------*/
219 /** @defgroup SPI_Exported_Functions SPI Exported Functions
220 * @{
223 /** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions
224 * @brief Initialization and Configuration functions
226 @verbatim
227 ===============================================================================
228 ##### Initialization and de-initialization functions #####
229 ===============================================================================
230 [..] This subsection provides a set of functions allowing to initialize and
231 de-initialize the SPIx peripheral:
233 (+) User must implement HAL_SPI_MspInit() function in which he configures
234 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
236 (+) Call the function HAL_SPI_Init() to configure the selected device with
237 the selected configuration:
238 (++) Mode
239 (++) Direction
240 (++) Data Size
241 (++) Clock Polarity and Phase
242 (++) NSS Management
243 (++) BaudRate Prescaler
244 (++) FirstBit
245 (++) TIMode
246 (++) CRC Calculation
247 (++) CRC Polynomial if CRC enabled
248 (++) CRC Length, used only with Data8 and Data16
249 (++) FIFO reception threshold
251 (+) Call the function HAL_SPI_DeInit() to restore the default configuration
252 of the selected SPIx peripheral.
254 @endverbatim
255 * @{
259 * @brief Initialize the SPI according to the specified parameters
260 * in the SPI_InitTypeDef and initialize the associated handle.
261 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
262 * the configuration information for SPI module.
263 * @retval HAL status
265 HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi)
267 uint32_t frxth;
269 /* Check the SPI handle allocation */
270 if (hspi == NULL)
272 return HAL_ERROR;
275 /* Check the parameters */
276 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
277 assert_param(IS_SPI_MODE(hspi->Init.Mode));
278 assert_param(IS_SPI_DIRECTION(hspi->Init.Direction));
279 assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize));
280 assert_param(IS_SPI_NSS(hspi->Init.NSS));
281 assert_param(IS_SPI_NSSP(hspi->Init.NSSPMode));
282 assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
283 assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit));
284 assert_param(IS_SPI_TIMODE(hspi->Init.TIMode));
285 if (hspi->Init.TIMode == SPI_TIMODE_DISABLE)
287 assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity));
288 assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase));
290 #if (USE_SPI_CRC != 0U)
291 assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation));
292 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
294 assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial));
295 assert_param(IS_SPI_CRC_LENGTH(hspi->Init.CRCLength));
297 #else
298 hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
299 #endif /* USE_SPI_CRC */
301 if (hspi->State == HAL_SPI_STATE_RESET)
303 /* Allocate lock resource and initialize it */
304 hspi->Lock = HAL_UNLOCKED;
306 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
307 HAL_SPI_MspInit(hspi);
310 hspi->State = HAL_SPI_STATE_BUSY;
312 /* Disable the selected SPI peripheral */
313 __HAL_SPI_DISABLE(hspi);
315 /* Align by default the rs fifo threshold on the data size */
316 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
318 frxth = SPI_RXFIFO_THRESHOLD_HF;
320 else
322 frxth = SPI_RXFIFO_THRESHOLD_QF;
325 /* CRC calculation is valid only for 16Bit and 8 Bit */
326 if ((hspi->Init.DataSize != SPI_DATASIZE_16BIT) && (hspi->Init.DataSize != SPI_DATASIZE_8BIT))
328 /* CRC must be disabled */
329 hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
332 /* Align the CRC Length on the data size */
333 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_DATASIZE)
335 /* CRC Length aligned on the data size : value set by default */
336 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
338 hspi->Init.CRCLength = SPI_CRC_LENGTH_16BIT;
340 else
342 hspi->Init.CRCLength = SPI_CRC_LENGTH_8BIT;
346 /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/
347 /* Configure : SPI Mode, Communication Mode, Clock polarity and phase, NSS management,
348 Communication speed, First bit, CRC calculation state */
349 WRITE_REG(hspi->Instance->CR1, (hspi->Init.Mode | hspi->Init.Direction |
350 hspi->Init.CLKPolarity | hspi->Init.CLKPhase | (hspi->Init.NSS & SPI_CR1_SSM) |
351 hspi->Init.BaudRatePrescaler | hspi->Init.FirstBit | hspi->Init.CRCCalculation));
352 #if (USE_SPI_CRC != 0U)
353 /* Configure : CRC Length */
354 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
356 hspi->Instance->CR1 |= SPI_CR1_CRCL;
358 #endif /* USE_SPI_CRC */
360 /* Configure : NSS management, TI Mode and Rx Fifo Threshold */
361 WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16) & SPI_CR2_SSOE) | hspi->Init.TIMode |
362 hspi->Init.NSSPMode | hspi->Init.DataSize) | frxth);
364 #if (USE_SPI_CRC != 0U)
365 /*---------------------------- SPIx CRCPOLY Configuration ------------------*/
366 /* Configure : CRC Polynomial */
367 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
369 WRITE_REG(hspi->Instance->CRCPR, hspi->Init.CRCPolynomial);
371 #endif /* USE_SPI_CRC */
373 #if defined(SPI_I2SCFGR_I2SMOD)
374 /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */
375 CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD);
376 #endif /* SPI_I2SCFGR_I2SMOD */
378 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
379 hspi->State = HAL_SPI_STATE_READY;
381 return HAL_OK;
385 * @brief De-Initialize the SPI peripheral.
386 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
387 * the configuration information for SPI module.
388 * @retval HAL status
390 HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi)
392 /* Check the SPI handle allocation */
393 if (hspi == NULL)
395 return HAL_ERROR;
398 /* Check SPI Instance parameter */
399 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
401 hspi->State = HAL_SPI_STATE_BUSY;
403 /* Disable the SPI Peripheral Clock */
404 __HAL_SPI_DISABLE(hspi);
406 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
407 HAL_SPI_MspDeInit(hspi);
409 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
410 hspi->State = HAL_SPI_STATE_RESET;
412 /* Release Lock */
413 __HAL_UNLOCK(hspi);
415 return HAL_OK;
419 * @brief Initialize the SPI MSP.
420 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
421 * the configuration information for SPI module.
422 * @retval None
424 __weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
426 /* Prevent unused argument(s) compilation warning */
427 UNUSED(hspi);
429 /* NOTE : This function should not be modified, when the callback is needed,
430 the HAL_SPI_MspInit should be implemented in the user file
435 * @brief De-Initialize the SPI MSP.
436 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
437 * the configuration information for SPI module.
438 * @retval None
440 __weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi)
442 /* Prevent unused argument(s) compilation warning */
443 UNUSED(hspi);
445 /* NOTE : This function should not be modified, when the callback is needed,
446 the HAL_SPI_MspDeInit should be implemented in the user file
451 * @}
454 /** @defgroup SPI_Exported_Functions_Group2 IO operation functions
455 * @brief Data transfers functions
457 @verbatim
458 ==============================================================================
459 ##### IO operation functions #####
460 ===============================================================================
461 [..]
462 This subsection provides a set of functions allowing to manage the SPI
463 data transfers.
465 [..] The SPI supports master and slave mode :
467 (#) There are two modes of transfer:
468 (++) Blocking mode: The communication is performed in polling mode.
469 The HAL status of all data processing is returned by the same function
470 after finishing transfer.
471 (++) No-Blocking mode: The communication is performed using Interrupts
472 or DMA, These APIs return the HAL status.
473 The end of the data processing will be indicated through the
474 dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when
475 using DMA mode.
476 The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks
477 will be executed respectively at the end of the transmit or Receive process
478 The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected
480 (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA)
481 exist for 1Line (simplex) and 2Lines (full duplex) modes.
483 @endverbatim
484 * @{
488 * @brief Transmit an amount of data in blocking mode.
489 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
490 * the configuration information for SPI module.
491 * @param pData: pointer to data buffer
492 * @param Size: amount of data to be sent
493 * @param Timeout: Timeout duration
494 * @retval HAL status
496 HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, const uint8_t *pData, uint16_t Size, uint32_t Timeout)
498 uint32_t tickstart = 0U;
499 HAL_StatusTypeDef errorcode = HAL_OK;
501 /* Check Direction parameter */
502 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
504 /* Process Locked */
505 __HAL_LOCK(hspi);
507 /* Init tickstart for timeout management*/
508 tickstart = HAL_GetTick();
510 if (hspi->State != HAL_SPI_STATE_READY)
512 errorcode = HAL_BUSY;
513 goto error;
516 if ((pData == NULL) || (Size == 0U))
518 errorcode = HAL_ERROR;
519 goto error;
522 /* Set the transaction information */
523 hspi->State = HAL_SPI_STATE_BUSY_TX;
524 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
525 hspi->pTxBuffPtr = (uint8_t *)pData;
526 hspi->TxXferSize = Size;
527 hspi->TxXferCount = Size;
529 /*Init field not used in handle to zero */
530 hspi->pRxBuffPtr = (uint8_t *)NULL;
531 hspi->RxXferSize = 0U;
532 hspi->RxXferCount = 0U;
533 hspi->TxISR = NULL;
534 hspi->RxISR = NULL;
536 /* Configure communication direction : 1Line */
537 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
539 SPI_1LINE_TX(hspi);
542 #if (USE_SPI_CRC != 0U)
543 /* Reset CRC Calculation */
544 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
546 SPI_RESET_CRC(hspi);
548 #endif /* USE_SPI_CRC */
550 /* Check if the SPI is already enabled */
551 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
553 /* Enable SPI peripheral */
554 __HAL_SPI_ENABLE(hspi);
557 /* Transmit data in 16 Bit mode */
558 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
560 /* Transmit data in 16 Bit mode */
561 while (hspi->TxXferCount > 0U)
563 /* Wait until TXE flag is set to send data */
564 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
566 hspi->Instance->DR = *((uint16_t *)pData);
567 pData += sizeof(uint16_t);
568 hspi->TxXferCount--;
570 else
572 /* Timeout management */
573 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
575 errorcode = HAL_TIMEOUT;
576 goto error;
581 /* Transmit data in 8 Bit mode */
582 else
584 while (hspi->TxXferCount > 0U)
586 /* Wait until TXE flag is set to send data */
587 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
589 if (hspi->TxXferCount > 1U)
591 /* write on the data register in packing mode */
592 hspi->Instance->DR = *((uint16_t *)pData);
593 pData += sizeof(uint16_t);
594 hspi->TxXferCount -= 2U;
596 else
598 *((__IO uint8_t *)&hspi->Instance->DR) = (*pData++);
599 hspi->TxXferCount--;
602 else
604 /* Timeout management */
605 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
607 errorcode = HAL_TIMEOUT;
608 goto error;
613 #if (USE_SPI_CRC != 0U)
614 /* Enable CRC Transmission */
615 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
617 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
619 #endif /* USE_SPI_CRC */
621 /* Check the end of the transaction */
622 if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
624 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
627 /* Clear overrun flag in 2 Lines communication mode because received is not read */
628 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
630 __HAL_SPI_CLEAR_OVRFLAG(hspi);
633 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
635 errorcode = HAL_ERROR;
638 error:
639 hspi->State = HAL_SPI_STATE_READY;
640 /* Process Unlocked */
641 __HAL_UNLOCK(hspi);
642 return errorcode;
646 * @brief Receive an amount of data in blocking mode.
647 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
648 * the configuration information for SPI module.
649 * @param pData: pointer to data buffer
650 * @param Size: amount of data to be received
651 * @param Timeout: Timeout duration
652 * @retval HAL status
654 HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
656 #if (USE_SPI_CRC != 0U)
657 __IO uint16_t tmpreg = 0U;
658 #endif /* USE_SPI_CRC */
659 uint32_t tickstart = 0U;
660 HAL_StatusTypeDef errorcode = HAL_OK;
662 if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES))
664 hspi->State = HAL_SPI_STATE_BUSY_RX;
665 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
666 return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout);
669 /* Process Locked */
670 __HAL_LOCK(hspi);
672 /* Init tickstart for timeout management*/
673 tickstart = HAL_GetTick();
675 if (hspi->State != HAL_SPI_STATE_READY)
677 errorcode = HAL_BUSY;
678 goto error;
681 if ((pData == NULL) || (Size == 0U))
683 errorcode = HAL_ERROR;
684 goto error;
687 /* Set the transaction information */
688 hspi->State = HAL_SPI_STATE_BUSY_RX;
689 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
690 hspi->pRxBuffPtr = (uint8_t *)pData;
691 hspi->RxXferSize = Size;
692 hspi->RxXferCount = Size;
694 /*Init field not used in handle to zero */
695 hspi->pTxBuffPtr = (uint8_t *)NULL;
696 hspi->TxXferSize = 0U;
697 hspi->TxXferCount = 0U;
698 hspi->RxISR = NULL;
699 hspi->TxISR = NULL;
701 #if (USE_SPI_CRC != 0U)
702 /* Reset CRC Calculation */
703 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
705 SPI_RESET_CRC(hspi);
706 /* this is done to handle the CRCNEXT before the latest data */
707 hspi->RxXferCount--;
709 #endif /* USE_SPI_CRC */
711 /* Set the Rx Fifo threshold */
712 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
714 /* set fiforxthreshold according the reception data length: 16bit */
715 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
717 else
719 /* set fiforxthreshold according the reception data length: 8bit */
720 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
723 /* Configure communication direction: 1Line */
724 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
726 SPI_1LINE_RX(hspi);
729 /* Check if the SPI is already enabled */
730 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
732 /* Enable SPI peripheral */
733 __HAL_SPI_ENABLE(hspi);
736 /* Receive data in 8 Bit mode */
737 if (hspi->Init.DataSize <= SPI_DATASIZE_8BIT)
739 /* Transfer loop */
740 while (hspi->RxXferCount > 0U)
742 /* Check the RXNE flag */
743 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
745 /* read the received data */
746 (*pData) = *(__IO uint8_t *)&hspi->Instance->DR;
747 pData += sizeof(uint8_t);
748 hspi->RxXferCount--;
750 else
752 /* Timeout management */
753 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
755 errorcode = HAL_TIMEOUT;
756 goto error;
761 else
763 /* Transfer loop */
764 while (hspi->RxXferCount > 0U)
766 /* Check the RXNE flag */
767 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
769 *((uint16_t *)pData) = hspi->Instance->DR;
770 pData += sizeof(uint16_t);
771 hspi->RxXferCount--;
773 else
775 /* Timeout management */
776 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
778 errorcode = HAL_TIMEOUT;
779 goto error;
785 #if (USE_SPI_CRC != 0U)
786 /* Handle the CRC Transmission */
787 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
789 /* freeze the CRC before the latest data */
790 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
792 /* Read the latest data */
793 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
795 /* the latest data has not been received */
796 errorcode = HAL_TIMEOUT;
797 goto error;
800 /* Receive last data in 16 Bit mode */
801 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
803 *((uint16_t *)pData) = hspi->Instance->DR;
805 /* Receive last data in 8 Bit mode */
806 else
808 (*pData) = *(__IO uint8_t *)&hspi->Instance->DR;
811 /* Wait the CRC data */
812 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
814 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
815 errorcode = HAL_TIMEOUT;
816 goto error;
819 /* Read CRC to Flush DR and RXNE flag */
820 if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
822 tmpreg = hspi->Instance->DR;
823 /* To avoid GCC warning */
824 UNUSED(tmpreg);
826 else
828 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
829 /* To avoid GCC warning */
830 UNUSED(tmpreg);
832 if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
834 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, Timeout, tickstart) != HAL_OK)
836 /* Error on the CRC reception */
837 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
838 errorcode = HAL_TIMEOUT;
839 goto error;
841 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
842 /* To avoid GCC warning */
843 UNUSED(tmpreg);
847 #endif /* USE_SPI_CRC */
849 /* Check the end of the transaction */
850 if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK)
852 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
855 #if (USE_SPI_CRC != 0U)
856 /* Check if CRC error occurred */
857 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
859 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
860 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
862 #endif /* USE_SPI_CRC */
864 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
866 errorcode = HAL_ERROR;
869 error :
870 hspi->State = HAL_SPI_STATE_READY;
871 __HAL_UNLOCK(hspi);
872 return errorcode;
876 * @brief Transmit and Receive an amount of data in blocking mode.
877 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
878 * the configuration information for SPI module.
879 * @param pTxData: pointer to transmission data buffer
880 * @param pRxData: pointer to reception data buffer
881 * @param Size: amount of data to be sent and received
882 * @param Timeout: Timeout duration
883 * @retval HAL status
885 HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, const uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
886 uint32_t Timeout)
888 uint32_t tmp = 0U, tmp1 = 0U;
889 #if (USE_SPI_CRC != 0U)
890 __IO uint16_t tmpreg = 0U;
891 #endif /* USE_SPI_CRC */
892 uint32_t tickstart = 0U;
893 /* Variable used to alternate Rx and Tx during transfer */
894 uint32_t txallowed = 1U;
895 HAL_StatusTypeDef errorcode = HAL_OK;
897 /* Check Direction parameter */
898 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
900 /* Process Locked */
901 __HAL_LOCK(hspi);
903 /* Init tickstart for timeout management*/
904 tickstart = HAL_GetTick();
906 tmp = hspi->State;
907 tmp1 = hspi->Init.Mode;
909 if (!((tmp == HAL_SPI_STATE_READY) || \
910 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
912 errorcode = HAL_BUSY;
913 goto error;
916 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
918 errorcode = HAL_ERROR;
919 goto error;
922 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
923 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
925 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
928 /* Set the transaction information */
929 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
930 hspi->pRxBuffPtr = (uint8_t *)pRxData;
931 hspi->RxXferCount = Size;
932 hspi->RxXferSize = Size;
933 hspi->pTxBuffPtr = (uint8_t *)pTxData;
934 hspi->TxXferCount = Size;
935 hspi->TxXferSize = Size;
937 /*Init field not used in handle to zero */
938 hspi->RxISR = NULL;
939 hspi->TxISR = NULL;
941 #if (USE_SPI_CRC != 0U)
942 /* Reset CRC Calculation */
943 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
945 SPI_RESET_CRC(hspi);
947 #endif /* USE_SPI_CRC */
949 /* Set the Rx Fifo threshold */
950 if ((hspi->Init.DataSize > SPI_DATASIZE_8BIT) || (hspi->RxXferCount > 1))
952 /* set fiforxthreshold according the reception data length: 16bit */
953 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
955 else
957 /* set fiforxthreshold according the reception data length: 8bit */
958 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
961 /* Check if the SPI is already enabled */
962 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
964 /* Enable SPI peripheral */
965 __HAL_SPI_ENABLE(hspi);
968 /* Transmit and Receive data in 16 Bit mode */
969 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
971 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01))
973 hspi->Instance->DR = *((uint16_t *)pTxData);
974 pTxData += sizeof(uint16_t);
975 hspi->TxXferCount--;
977 while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
979 /* Check TXE flag */
980 if (txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
982 hspi->Instance->DR = *((uint16_t *)pTxData);
983 pTxData += sizeof(uint16_t);
984 hspi->TxXferCount--;
985 /* Next Data is a reception (Rx). Tx not allowed */
986 txallowed = 0U;
988 #if (USE_SPI_CRC != 0U)
989 /* Enable CRC Transmission */
990 if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
992 /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
993 if (((hspi->Instance->CR1 & SPI_CR1_MSTR) == 0U) && ((hspi->Instance->CR2 & SPI_CR2_NSSP) == SPI_CR2_NSSP))
995 SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
997 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
999 #endif /* USE_SPI_CRC */
1002 /* Check RXNE flag */
1003 if ((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
1005 *((uint16_t *)pRxData) = hspi->Instance->DR;
1006 pRxData += sizeof(uint16_t);
1007 hspi->RxXferCount--;
1008 /* Next Data is a Transmission (Tx). Tx is allowed */
1009 txallowed = 1U;
1011 if ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout))
1013 errorcode = HAL_TIMEOUT;
1014 goto error;
1018 /* Transmit and Receive data in 8 Bit mode */
1019 else
1021 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01))
1023 *((__IO uint8_t *)&hspi->Instance->DR) = (*pTxData);
1024 pTxData += sizeof(uint8_t);
1025 hspi->TxXferCount--;
1027 while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
1029 /* check TXE flag */
1030 if (txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
1032 if (hspi->TxXferCount > 1U)
1034 hspi->Instance->DR = *((uint16_t *)pTxData);
1035 pTxData += sizeof(uint16_t);
1036 hspi->TxXferCount -= 2U;
1038 else
1040 *(__IO uint8_t *)&hspi->Instance->DR = (*pTxData++);
1041 hspi->TxXferCount--;
1043 /* Next Data is a reception (Rx). Tx not allowed */
1044 txallowed = 0U;
1046 #if (USE_SPI_CRC != 0U)
1047 /* Enable CRC Transmission */
1048 if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
1050 /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
1051 if (((hspi->Instance->CR1 & SPI_CR1_MSTR) == 0U) && ((hspi->Instance->CR2 & SPI_CR2_NSSP) == SPI_CR2_NSSP))
1053 SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
1055 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
1057 #endif /* USE_SPI_CRC */
1060 /* Wait until RXNE flag is reset */
1061 if ((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
1063 if (hspi->RxXferCount > 1U)
1065 *((uint16_t *)pRxData) = hspi->Instance->DR;
1066 pRxData += sizeof(uint16_t);
1067 hspi->RxXferCount -= 2U;
1068 if (hspi->RxXferCount <= 1U)
1070 /* set fiforxthreshold before to switch on 8 bit data size */
1071 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1074 else
1076 (*pRxData++) = *(__IO uint8_t *)&hspi->Instance->DR;
1077 hspi->RxXferCount--;
1079 /* Next Data is a Transmission (Tx). Tx is allowed */
1080 txallowed = 1U;
1082 if ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout))
1084 errorcode = HAL_TIMEOUT;
1085 goto error;
1090 #if (USE_SPI_CRC != 0U)
1091 /* Read CRC from DR to close CRC calculation process */
1092 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1094 /* Wait until TXE flag */
1095 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
1097 /* Error on the CRC reception */
1098 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1099 errorcode = HAL_TIMEOUT;
1100 goto error;
1102 /* Read CRC */
1103 if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
1105 tmpreg = hspi->Instance->DR;
1106 /* To avoid GCC warning */
1107 UNUSED(tmpreg);
1109 else
1111 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
1112 /* To avoid GCC warning */
1113 UNUSED(tmpreg);
1115 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
1117 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
1119 /* Error on the CRC reception */
1120 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1121 errorcode = HAL_TIMEOUT;
1122 goto error;
1124 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
1125 /* To avoid GCC warning */
1126 UNUSED(tmpreg);
1131 /* Check if CRC error occurred */
1132 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
1134 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1135 /* Clear CRC Flag */
1136 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
1138 errorcode = HAL_ERROR;
1140 #endif /* USE_SPI_CRC */
1142 /* Check the end of the transaction */
1143 if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
1145 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
1148 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
1150 errorcode = HAL_ERROR;
1153 error :
1154 hspi->State = HAL_SPI_STATE_READY;
1155 __HAL_UNLOCK(hspi);
1156 return errorcode;
1160 * @brief Transmit an amount of data in non-blocking mode with Interrupt.
1161 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1162 * the configuration information for SPI module.
1163 * @param pData: pointer to data buffer
1164 * @param Size: amount of data to be sent
1165 * @retval HAL status
1167 HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1169 HAL_StatusTypeDef errorcode = HAL_OK;
1171 /* Check Direction parameter */
1172 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1174 /* Process Locked */
1175 __HAL_LOCK(hspi);
1177 if ((pData == NULL) || (Size == 0U))
1179 errorcode = HAL_ERROR;
1180 goto error;
1183 if (hspi->State != HAL_SPI_STATE_READY)
1185 errorcode = HAL_BUSY;
1186 goto error;
1189 /* Set the transaction information */
1190 hspi->State = HAL_SPI_STATE_BUSY_TX;
1191 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1192 hspi->pTxBuffPtr = (uint8_t *)pData;
1193 hspi->TxXferSize = Size;
1194 hspi->TxXferCount = Size;
1196 /* Init field not used in handle to zero */
1197 hspi->pRxBuffPtr = (uint8_t *)NULL;
1198 hspi->RxXferSize = 0U;
1199 hspi->RxXferCount = 0U;
1200 hspi->RxISR = NULL;
1202 /* Set the function for IT treatment */
1203 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1205 hspi->TxISR = SPI_TxISR_16BIT;
1207 else
1209 hspi->TxISR = SPI_TxISR_8BIT;
1212 /* Configure communication direction : 1Line */
1213 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1215 SPI_1LINE_TX(hspi);
1218 #if (USE_SPI_CRC != 0U)
1219 /* Reset CRC Calculation */
1220 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1222 SPI_RESET_CRC(hspi);
1224 #endif /* USE_SPI_CRC */
1226 /* Enable TXE and ERR interrupt */
1227 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
1230 /* Check if the SPI is already enabled */
1231 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1233 /* Enable SPI peripheral */
1234 __HAL_SPI_ENABLE(hspi);
1237 error :
1238 __HAL_UNLOCK(hspi);
1239 return errorcode;
1243 * @brief Receive an amount of data in non-blocking mode with Interrupt.
1244 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1245 * the configuration information for SPI module.
1246 * @param pData: pointer to data buffer
1247 * @param Size: amount of data to be sent
1248 * @retval HAL status
1250 HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1252 HAL_StatusTypeDef errorcode = HAL_OK;
1254 if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
1256 hspi->State = HAL_SPI_STATE_BUSY_RX;
1257 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1258 return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size);
1261 /* Process Locked */
1262 __HAL_LOCK(hspi);
1264 if (hspi->State != HAL_SPI_STATE_READY)
1266 errorcode = HAL_BUSY;
1267 goto error;
1270 if ((pData == NULL) || (Size == 0U))
1272 errorcode = HAL_ERROR;
1273 goto error;
1276 /* Set the transaction information */
1277 hspi->State = HAL_SPI_STATE_BUSY_RX;
1278 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1279 hspi->pRxBuffPtr = (uint8_t *)pData;
1280 hspi->RxXferSize = Size;
1281 hspi->RxXferCount = Size;
1283 /* Init field not used in handle to zero */
1284 hspi->pTxBuffPtr = (uint8_t *)NULL;
1285 hspi->TxXferSize = 0U;
1286 hspi->TxXferCount = 0U;
1287 hspi->TxISR = NULL;
1289 /* check the data size to adapt Rx threshold and the set the function for IT treatment */
1290 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1292 /* set fiforxthreshold according the reception data length: 16 bit */
1293 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1294 hspi->RxISR = SPI_RxISR_16BIT;
1296 else
1298 /* set fiforxthreshold according the reception data length: 8 bit */
1299 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1300 hspi->RxISR = SPI_RxISR_8BIT;
1303 /* Configure communication direction : 1Line */
1304 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1306 SPI_1LINE_RX(hspi);
1309 #if (USE_SPI_CRC != 0U)
1310 /* Reset CRC Calculation */
1311 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1313 hspi->CRCSize = 1U;
1314 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
1316 hspi->CRCSize = 2U;
1318 SPI_RESET_CRC(hspi);
1320 else
1322 hspi->CRCSize = 0U;
1324 #endif /* USE_SPI_CRC */
1326 /* Enable TXE and ERR interrupt */
1327 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
1329 /* Note : The SPI must be enabled after unlocking current process
1330 to avoid the risk of SPI interrupt handle execution before current
1331 process unlock */
1333 /* Check if the SPI is already enabled */
1334 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1336 /* Enable SPI peripheral */
1337 __HAL_SPI_ENABLE(hspi);
1340 error :
1341 /* Process Unlocked */
1342 __HAL_UNLOCK(hspi);
1343 return errorcode;
1347 * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt.
1348 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1349 * the configuration information for SPI module.
1350 * @param pTxData: pointer to transmission data buffer
1351 * @param pRxData: pointer to reception data buffer
1352 * @param Size: amount of data to be sent and received
1353 * @retval HAL status
1355 HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
1357 uint32_t tmp = 0U, tmp1 = 0U;
1358 HAL_StatusTypeDef errorcode = HAL_OK;
1360 /* Check Direction parameter */
1361 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1363 /* Process locked */
1364 __HAL_LOCK(hspi);
1366 tmp = hspi->State;
1367 tmp1 = hspi->Init.Mode;
1369 if (!((tmp == HAL_SPI_STATE_READY) || \
1370 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1372 errorcode = HAL_BUSY;
1373 goto error;
1376 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
1378 errorcode = HAL_ERROR;
1379 goto error;
1382 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1383 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
1385 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1388 /* Set the transaction information */
1389 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1390 hspi->pTxBuffPtr = (uint8_t *)pTxData;
1391 hspi->TxXferSize = Size;
1392 hspi->TxXferCount = Size;
1393 hspi->pRxBuffPtr = (uint8_t *)pRxData;
1394 hspi->RxXferSize = Size;
1395 hspi->RxXferCount = Size;
1397 /* Set the function for IT treatment */
1398 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1400 hspi->RxISR = SPI_2linesRxISR_16BIT;
1401 hspi->TxISR = SPI_2linesTxISR_16BIT;
1403 else
1405 hspi->RxISR = SPI_2linesRxISR_8BIT;
1406 hspi->TxISR = SPI_2linesTxISR_8BIT;
1409 #if (USE_SPI_CRC != 0U)
1410 /* Reset CRC Calculation */
1411 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1413 hspi->CRCSize = 1U;
1414 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
1416 hspi->CRCSize = 2U;
1418 SPI_RESET_CRC(hspi);
1420 else
1422 hspi->CRCSize = 0U;
1424 #endif /* USE_SPI_CRC */
1426 /* check if packing mode is enabled and if there is more than 2 data to receive */
1427 if ((hspi->Init.DataSize > SPI_DATASIZE_8BIT) || (hspi->RxXferCount >= 2U))
1429 /* set fiforxthreshold according the reception data length: 16 bit */
1430 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1432 else
1434 /* set fiforxthreshold according the reception data length: 8 bit */
1435 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1438 /* Enable TXE, RXNE and ERR interrupt */
1439 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
1441 /* Check if the SPI is already enabled */
1442 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1444 /* Enable SPI peripheral */
1445 __HAL_SPI_ENABLE(hspi);
1448 error :
1449 /* Process Unlocked */
1450 __HAL_UNLOCK(hspi);
1451 return errorcode;
1455 * @brief Transmit an amount of data in non-blocking mode with DMA.
1456 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1457 * the configuration information for SPI module.
1458 * @param pData: pointer to data buffer
1459 * @param Size: amount of data to be sent
1460 * @retval HAL status
1462 HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1464 HAL_StatusTypeDef errorcode = HAL_OK;
1466 /* Check Direction parameter */
1467 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1469 /* Process Locked */
1470 __HAL_LOCK(hspi);
1472 if (hspi->State != HAL_SPI_STATE_READY)
1474 errorcode = HAL_BUSY;
1475 goto error;
1478 if ((pData == NULL) || (Size == 0U))
1480 errorcode = HAL_ERROR;
1481 goto error;
1484 /* Set the transaction information */
1485 hspi->State = HAL_SPI_STATE_BUSY_TX;
1486 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1487 hspi->pTxBuffPtr = (uint8_t *)pData;
1488 hspi->TxXferSize = Size;
1489 hspi->TxXferCount = Size;
1491 /* Init field not used in handle to zero */
1492 hspi->pRxBuffPtr = (uint8_t *)NULL;
1493 hspi->TxISR = NULL;
1494 hspi->RxISR = NULL;
1495 hspi->RxXferSize = 0U;
1496 hspi->RxXferCount = 0U;
1498 /* Configure communication direction : 1Line */
1499 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1501 SPI_1LINE_TX(hspi);
1504 #if (USE_SPI_CRC != 0U)
1505 /* Reset CRC Calculation */
1506 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1508 SPI_RESET_CRC(hspi);
1510 #endif /* USE_SPI_CRC */
1512 /* Set the SPI TxDMA Half transfer complete callback */
1513 hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt;
1515 /* Set the SPI TxDMA transfer complete callback */
1516 hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt;
1518 /* Set the DMA error callback */
1519 hspi->hdmatx->XferErrorCallback = SPI_DMAError;
1521 /* Set the DMA AbortCpltCallback */
1522 hspi->hdmatx->XferAbortCallback = NULL;
1524 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1525 /* packing mode is enabled only if the DMA setting is HALWORD */
1526 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
1528 /* Check the even/odd of the data size + crc if enabled */
1529 if ((hspi->TxXferCount & 0x1U) == 0U)
1531 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1532 hspi->TxXferCount = (hspi->TxXferCount >> 1U);
1534 else
1536 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1537 hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
1541 /* Enable the Tx DMA Stream/Channel */
1542 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1544 /* Check if the SPI is already enabled */
1545 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1547 /* Enable SPI peripheral */
1548 __HAL_SPI_ENABLE(hspi);
1551 /* Enable the SPI Error Interrupt Bit */
1552 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1554 /* Enable Tx DMA Request */
1555 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1557 error :
1558 /* Process Unlocked */
1559 __HAL_UNLOCK(hspi);
1560 return errorcode;
1564 * @brief Receive an amount of data in non-blocking mode with DMA.
1565 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1566 * the configuration information for SPI module.
1567 * @param pData: pointer to data buffer
1568 * @note When the CRC feature is enabled the pData Length must be Size + 1.
1569 * @param Size: amount of data to be sent
1570 * @retval HAL status
1572 HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1574 HAL_StatusTypeDef errorcode = HAL_OK;
1576 if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
1578 hspi->State = HAL_SPI_STATE_BUSY_RX;
1579 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1580 return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size);
1583 /* Process Locked */
1584 __HAL_LOCK(hspi);
1586 if (hspi->State != HAL_SPI_STATE_READY)
1588 errorcode = HAL_BUSY;
1589 goto error;
1592 if ((pData == NULL) || (Size == 0U))
1594 errorcode = HAL_ERROR;
1595 goto error;
1598 /* Set the transaction information */
1599 hspi->State = HAL_SPI_STATE_BUSY_RX;
1600 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1601 hspi->pRxBuffPtr = (uint8_t *)pData;
1602 hspi->RxXferSize = Size;
1603 hspi->RxXferCount = Size;
1605 /*Init field not used in handle to zero */
1606 hspi->RxISR = NULL;
1607 hspi->TxISR = NULL;
1608 hspi->TxXferSize = 0U;
1609 hspi->TxXferCount = 0U;
1611 /* Configure communication direction : 1Line */
1612 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1614 SPI_1LINE_RX(hspi);
1617 #if (USE_SPI_CRC != 0U)
1618 /* Reset CRC Calculation */
1619 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1621 SPI_RESET_CRC(hspi);
1623 #endif /* USE_SPI_CRC */
1625 /* packing mode management is enabled by the DMA settings */
1626 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
1628 /* Restriction the DMA data received is not allowed in this mode */
1629 errorcode = HAL_ERROR;
1630 goto error;
1633 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1634 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1636 /* set fiforxthreshold according the reception data length: 16bit */
1637 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1639 else
1641 /* set fiforxthreshold according the reception data length: 8bit */
1642 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1645 /* Set the SPI RxDMA Half transfer complete callback */
1646 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1648 /* Set the SPI Rx DMA transfer complete callback */
1649 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1651 /* Set the DMA error callback */
1652 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1654 /* Set the DMA AbortCpltCallback */
1655 hspi->hdmarx->XferAbortCallback = NULL;
1657 /* Enable the Rx DMA Stream/Channel */
1658 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1660 /* Check if the SPI is already enabled */
1661 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1663 /* Enable SPI peripheral */
1664 __HAL_SPI_ENABLE(hspi);
1667 /* Enable the SPI Error Interrupt Bit */
1668 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1670 /* Enable Rx DMA Request */
1671 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1673 error:
1674 /* Process Unlocked */
1675 __HAL_UNLOCK(hspi);
1676 return errorcode;
1680 * @brief Transmit and Receive an amount of data in non-blocking mode with DMA.
1681 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1682 * the configuration information for SPI module.
1683 * @param pTxData: pointer to transmission data buffer
1684 * @param pRxData: pointer to reception data buffer
1685 * @note When the CRC feature is enabled the pRxData Length must be Size + 1
1686 * @param Size: amount of data to be sent
1687 * @retval HAL status
1689 HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData,
1690 uint16_t Size)
1692 uint32_t tmp = 0U, tmp1 = 0U;
1693 HAL_StatusTypeDef errorcode = HAL_OK;
1695 /* Check Direction parameter */
1696 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1698 /* Process locked */
1699 __HAL_LOCK(hspi);
1701 tmp = hspi->State;
1702 tmp1 = hspi->Init.Mode;
1703 if (!((tmp == HAL_SPI_STATE_READY) ||
1704 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1706 errorcode = HAL_BUSY;
1707 goto error;
1710 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
1712 errorcode = HAL_ERROR;
1713 goto error;
1716 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1717 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
1719 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1722 /* Set the transaction information */
1723 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1724 hspi->pTxBuffPtr = (uint8_t *)pTxData;
1725 hspi->TxXferSize = Size;
1726 hspi->TxXferCount = Size;
1727 hspi->pRxBuffPtr = (uint8_t *)pRxData;
1728 hspi->RxXferSize = Size;
1729 hspi->RxXferCount = Size;
1731 /* Init field not used in handle to zero */
1732 hspi->RxISR = NULL;
1733 hspi->TxISR = NULL;
1735 #if (USE_SPI_CRC != 0U)
1736 /* Reset CRC Calculation */
1737 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1739 SPI_RESET_CRC(hspi);
1741 #endif /* USE_SPI_CRC */
1743 /* Reset the threshold bit */
1744 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX | SPI_CR2_LDMARX);
1746 /* the packing mode management is enabled by the DMA settings according the spi data size */
1747 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1749 /* set fiforxthreshold according the reception data length: 16bit */
1750 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1752 else
1754 /* set fiforxthreshold according the reception data length: 8bit */
1755 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1757 if (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1759 if ((hspi->TxXferSize & 0x1U) == 0x0U)
1761 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1762 hspi->TxXferCount = hspi->TxXferCount >> 1U;
1764 else
1766 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1767 hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
1771 if (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1773 /* set fiforxthreshold according the reception data length: 16bit */
1774 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1776 if ((hspi->RxXferCount & 0x1U) == 0x0U)
1778 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1779 hspi->RxXferCount = hspi->RxXferCount >> 1U;
1781 else
1783 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1784 hspi->RxXferCount = (hspi->RxXferCount >> 1U) + 1U;
1789 /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */
1790 if (hspi->State == HAL_SPI_STATE_BUSY_RX)
1792 /* Set the SPI Rx DMA Half transfer complete callback */
1793 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1794 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1796 else
1798 /* Set the SPI Tx/Rx DMA Half transfer complete callback */
1799 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt;
1800 hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt;
1803 /* Set the DMA error callback */
1804 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1806 /* Set the DMA AbortCpltCallback */
1807 hspi->hdmarx->XferAbortCallback = NULL;
1809 /* Enable the Rx DMA Stream/Channel */
1810 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1812 /* Enable Rx DMA Request */
1813 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1815 /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing
1816 is performed in DMA reception complete callback */
1817 hspi->hdmatx->XferHalfCpltCallback = NULL;
1818 hspi->hdmatx->XferCpltCallback = NULL;
1819 hspi->hdmatx->XferErrorCallback = NULL;
1820 hspi->hdmatx->XferAbortCallback = NULL;
1822 /* Enable the Tx DMA Stream/Channel */
1823 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1825 /* Check if the SPI is already enabled */
1826 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1828 /* Enable SPI peripheral */
1829 __HAL_SPI_ENABLE(hspi);
1831 /* Enable the SPI Error Interrupt Bit */
1832 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1834 /* Enable Tx DMA Request */
1835 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1837 error :
1838 /* Process Unlocked */
1839 __HAL_UNLOCK(hspi);
1840 return errorcode;
1844 * @brief Abort ongoing transfer (blocking mode).
1845 * @param hspi SPI handle.
1846 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
1847 * started in Interrupt or DMA mode.
1848 * This procedure performs following operations :
1849 * - Disable SPI Interrupts (depending of transfer direction)
1850 * - Disable the DMA transfer in the peripheral register (if enabled)
1851 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1852 * - Set handle State to READY
1853 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1854 * @retval HAL status
1856 HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi)
1858 HAL_StatusTypeDef errorcode;
1859 uint32_t tickstart = 0U;
1861 /* Initialized local variable */
1862 errorcode = HAL_OK;
1864 /* Init tickstart for timeout managment*/
1865 tickstart = HAL_GetTick();
1867 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
1868 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
1870 hspi->TxISR = SPI_AbortTx_ISR;
1873 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
1875 hspi->RxISR = SPI_AbortRx_ISR;
1878 while (hspi->State != HAL_SPI_STATE_ABORT)
1880 if ((HAL_GetTick() - tickstart) >= HAL_MAX_DELAY)
1882 return HAL_TIMEOUT;
1886 /* Clear ERRIE interrupts in case of DMA Mode */
1887 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1889 /* Disable the SPI DMA Tx or SPI DMA Rx request if enabled */
1890 if ((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
1892 /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */
1893 if (hspi->hdmatx != NULL)
1895 /* Set the SPI DMA Abort callback :
1896 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
1897 hspi->hdmatx->XferAbortCallback = NULL;
1899 /* Abort DMA Tx Handle linked to SPI Peripheral */
1900 if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK)
1902 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1905 /* Disable Tx DMA Request */
1906 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN));
1908 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
1910 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1913 /* Disable SPI Peripheral */
1914 __HAL_SPI_DISABLE(hspi);
1916 /* Empty the FRLVL fifo */
1917 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
1919 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1922 /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */
1923 if (hspi->hdmarx != NULL)
1925 /* Set the SPI DMA Abort callback :
1926 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
1927 hspi->hdmarx->XferAbortCallback = NULL;
1929 /* Abort DMA Rx Handle linked to SPI Peripheral */
1930 if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK)
1932 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1935 /* Disable peripheral */
1936 __HAL_SPI_DISABLE(hspi);
1938 /* Control the BSY flag */
1939 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
1941 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1944 /* Empty the FRLVL fifo */
1945 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
1947 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
1950 /* Disable Rx DMA Request */
1951 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN));
1954 /* Reset Tx and Rx transfer counters */
1955 hspi->RxXferCount = 0U;
1956 hspi->TxXferCount = 0U;
1958 /* Check error during Abort procedure */
1959 if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
1961 /* return HAL_Error in case of error during Abort procedure */
1962 errorcode = HAL_ERROR;
1964 else
1966 /* Reset errorCode */
1967 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1970 /* Clear the Error flags in the SR register */
1971 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1972 __HAL_SPI_CLEAR_FREFLAG(hspi);
1974 /* Restore hspi->state to ready */
1975 hspi->State = HAL_SPI_STATE_READY;
1977 return errorcode;
1981 * @brief Abort ongoing transfer (Interrupt mode).
1982 * @param hspi SPI handle.
1983 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
1984 * started in Interrupt or DMA mode.
1985 * This procedure performs following operations :
1986 * - Disable SPI Interrupts (depending of transfer direction)
1987 * - Disable the DMA transfer in the peripheral register (if enabled)
1988 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1989 * - Set handle State to READY
1990 * - At abort completion, call user abort complete callback
1991 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1992 * considered as completed only when user abort complete callback is executed (not when exiting function).
1993 * @retval HAL status
1995 HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi)
1997 HAL_StatusTypeDef errorcode;
1998 uint32_t tickstart = 0U;
1999 uint32_t abortcplt ;
2001 /* Initialized local variable */
2002 errorcode = HAL_OK;
2003 abortcplt = 1U;
2005 /* Init tickstart for timeout managment*/
2006 tickstart = HAL_GetTick();
2008 /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */
2009 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
2011 hspi->TxISR = SPI_AbortTx_ISR;
2014 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
2016 hspi->RxISR = SPI_AbortRx_ISR;
2019 while (hspi->State != HAL_SPI_STATE_ABORT)
2021 if ((HAL_GetTick() - tickstart) >= HAL_MAX_DELAY)
2023 return HAL_TIMEOUT;
2027 /* Clear ERRIE interrupts in case of DMA Mode */
2028 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
2030 /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised
2031 before any call to DMA Abort functions */
2032 /* DMA Tx Handle is valid */
2033 if (hspi->hdmatx != NULL)
2035 /* Set DMA Abort Complete callback if UART DMA Tx request if enabled.
2036 Otherwise, set it to NULL */
2037 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
2039 hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback;
2041 else
2043 hspi->hdmatx->XferAbortCallback = NULL;
2046 /* DMA Rx Handle is valid */
2047 if (hspi->hdmarx != NULL)
2049 /* Set DMA Abort Complete callback if UART DMA Rx request if enabled.
2050 Otherwise, set it to NULL */
2051 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
2053 hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback;
2055 else
2057 hspi->hdmarx->XferAbortCallback = NULL;
2061 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2062 if ((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) && (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
2064 /* Abort the SPI DMA Tx Stream/Channel */
2065 if (hspi->hdmatx != NULL)
2067 /* Abort DMA Tx Handle linked to SPI Peripheral */
2068 if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
2070 hspi->hdmatx->XferAbortCallback = NULL;
2071 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2073 else
2075 abortcplt = 0U;
2078 /* Abort the SPI DMA Rx Stream/Channel */
2079 if (hspi->hdmarx != NULL)
2081 /* Abort DMA Rx Handle linked to SPI Peripheral */
2082 if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK)
2084 hspi->hdmarx->XferAbortCallback = NULL;
2085 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2086 abortcplt = 1U;
2088 else
2090 abortcplt = 0U;
2095 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2096 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
2098 /* Abort the SPI DMA Tx Stream/Channel */
2099 if (hspi->hdmatx != NULL)
2101 /* Abort DMA Tx Handle linked to SPI Peripheral */
2102 if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
2104 hspi->hdmatx->XferAbortCallback = NULL;
2105 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2107 else
2109 abortcplt = 0U;
2113 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2114 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
2116 /* Abort the SPI DMA Rx Stream/Channel */
2117 if (hspi->hdmarx != NULL)
2119 /* Abort DMA Rx Handle linked to SPI Peripheral */
2120 if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK)
2122 hspi->hdmarx->XferAbortCallback = NULL;
2123 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2125 else
2127 abortcplt = 0U;
2132 if (abortcplt == 1U)
2134 /* Reset Tx and Rx transfer counters */
2135 hspi->RxXferCount = 0U;
2136 hspi->TxXferCount = 0U;
2138 /* Check error during Abort procedure */
2139 if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
2141 /* return HAL_Error in case of error during Abort procedure */
2142 errorcode = HAL_ERROR;
2144 else
2146 /* Reset errorCode */
2147 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2150 /* Clear the Error flags in the SR register */
2151 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2152 __HAL_SPI_CLEAR_FREFLAG(hspi);
2154 /* Restore hspi->State to Ready */
2155 hspi->State = HAL_SPI_STATE_READY;
2157 /* As no DMA to be aborted, call directly user Abort complete callback */
2158 HAL_SPI_AbortCpltCallback(hspi);
2161 return errorcode;
2165 * @brief Pause the DMA Transfer.
2166 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2167 * the configuration information for the specified SPI module.
2168 * @retval HAL status
2170 HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi)
2172 /* Process Locked */
2173 __HAL_LOCK(hspi);
2175 /* Disable the SPI DMA Tx & Rx requests */
2176 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2178 /* Process Unlocked */
2179 __HAL_UNLOCK(hspi);
2181 return HAL_OK;
2185 * @brief Resume the DMA Transfer.
2186 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2187 * the configuration information for the specified SPI module.
2188 * @retval HAL status
2190 HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi)
2192 /* Process Locked */
2193 __HAL_LOCK(hspi);
2195 /* Enable the SPI DMA Tx & Rx requests */
2196 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2198 /* Process Unlocked */
2199 __HAL_UNLOCK(hspi);
2201 return HAL_OK;
2205 * @brief Stop the DMA Transfer.
2206 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2207 * the configuration information for the specified SPI module.
2208 * @retval HAL status
2210 HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi)
2212 /* The Lock is not implemented on this API to allow the user application
2213 to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback():
2214 when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
2215 and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback()
2218 /* Abort the SPI DMA tx Stream/Channel */
2219 if (hspi->hdmatx != NULL)
2221 HAL_DMA_Abort(hspi->hdmatx);
2223 /* Abort the SPI DMA rx Stream/Channel */
2224 if (hspi->hdmarx != NULL)
2226 HAL_DMA_Abort(hspi->hdmarx);
2229 /* Disable the SPI DMA Tx & Rx requests */
2230 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2231 hspi->State = HAL_SPI_STATE_READY;
2232 return HAL_OK;
2236 * @brief Handle SPI interrupt request.
2237 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2238 * the configuration information for the specified SPI module.
2239 * @retval None
2241 void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi)
2243 uint32_t itsource = hspi->Instance->CR2;
2244 uint32_t itflag = hspi->Instance->SR;
2246 /* SPI in mode Receiver ----------------------------------------------------*/
2247 if (((itflag & SPI_FLAG_OVR) == RESET) &&
2248 ((itflag & SPI_FLAG_RXNE) != RESET) && ((itsource & SPI_IT_RXNE) != RESET))
2250 hspi->RxISR(hspi);
2251 return;
2254 /* SPI in mode Transmitter -------------------------------------------------*/
2255 if (((itflag & SPI_FLAG_TXE) != RESET) && ((itsource & SPI_IT_TXE) != RESET))
2257 hspi->TxISR(hspi);
2258 return;
2261 /* SPI in Error Treatment --------------------------------------------------*/
2262 if (((itflag & (SPI_FLAG_MODF | SPI_FLAG_OVR | SPI_FLAG_FRE)) != RESET) && ((itsource & SPI_IT_ERR) != RESET))
2264 /* SPI Overrun error interrupt occurred ----------------------------------*/
2265 if ((itflag & SPI_FLAG_OVR) != RESET)
2267 if (hspi->State != HAL_SPI_STATE_BUSY_TX)
2269 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR);
2270 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2272 else
2274 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2275 return;
2279 /* SPI Mode Fault error interrupt occurred -------------------------------*/
2280 if ((itflag & SPI_FLAG_MODF) != RESET)
2282 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF);
2283 __HAL_SPI_CLEAR_MODFFLAG(hspi);
2286 /* SPI Frame error interrupt occurred ------------------------------------*/
2287 if ((itflag & SPI_FLAG_FRE) != RESET)
2289 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE);
2290 __HAL_SPI_CLEAR_FREFLAG(hspi);
2293 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2295 /* Disable all interrupts */
2296 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR);
2298 hspi->State = HAL_SPI_STATE_READY;
2299 /* Disable the SPI DMA requests if enabled */
2300 if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN)))
2302 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN));
2304 /* Abort the SPI DMA Rx channel */
2305 if (hspi->hdmarx != NULL)
2307 /* Set the SPI DMA Abort callback :
2308 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2309 hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError;
2310 HAL_DMA_Abort_IT(hspi->hdmarx);
2312 /* Abort the SPI DMA Tx channel */
2313 if (hspi->hdmatx != NULL)
2315 /* Set the SPI DMA Abort callback :
2316 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2317 hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError;
2318 HAL_DMA_Abort_IT(hspi->hdmatx);
2321 else
2323 /* Call user error callback */
2324 HAL_SPI_ErrorCallback(hspi);
2327 return;
2332 * @brief Tx Transfer completed callback.
2333 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2334 * the configuration information for SPI module.
2335 * @retval None
2337 __weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi)
2339 /* Prevent unused argument(s) compilation warning */
2340 UNUSED(hspi);
2342 /* NOTE : This function should not be modified, when the callback is needed,
2343 the HAL_SPI_TxCpltCallback should be implemented in the user file
2348 * @brief Rx Transfer completed callback.
2349 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2350 * the configuration information for SPI module.
2351 * @retval None
2353 __weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi)
2355 /* Prevent unused argument(s) compilation warning */
2356 UNUSED(hspi);
2358 /* NOTE : This function should not be modified, when the callback is needed,
2359 the HAL_SPI_RxCpltCallback should be implemented in the user file
2364 * @brief Tx and Rx Transfer completed callback.
2365 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2366 * the configuration information for SPI module.
2367 * @retval None
2369 __weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi)
2371 /* Prevent unused argument(s) compilation warning */
2372 UNUSED(hspi);
2374 /* NOTE : This function should not be modified, when the callback is needed,
2375 the HAL_SPI_TxRxCpltCallback should be implemented in the user file
2380 * @brief Tx Half Transfer completed callback.
2381 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2382 * the configuration information for SPI module.
2383 * @retval None
2385 __weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2387 /* Prevent unused argument(s) compilation warning */
2388 UNUSED(hspi);
2390 /* NOTE : This function should not be modified, when the callback is needed,
2391 the HAL_SPI_TxHalfCpltCallback should be implemented in the user file
2396 * @brief Rx Half Transfer completed callback.
2397 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2398 * the configuration information for SPI module.
2399 * @retval None
2401 __weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2403 /* Prevent unused argument(s) compilation warning */
2404 UNUSED(hspi);
2406 /* NOTE : This function should not be modified, when the callback is needed,
2407 the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file
2412 * @brief Tx and Rx Half Transfer callback.
2413 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2414 * the configuration information for SPI module.
2415 * @retval None
2417 __weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2419 /* Prevent unused argument(s) compilation warning */
2420 UNUSED(hspi);
2422 /* NOTE : This function should not be modified, when the callback is needed,
2423 the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file
2428 * @brief SPI error callback.
2429 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2430 * the configuration information for SPI module.
2431 * @retval None
2433 __weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi)
2435 /* Prevent unused argument(s) compilation warning */
2436 UNUSED(hspi);
2438 /* NOTE : This function should not be modified, when the callback is needed,
2439 the HAL_SPI_ErrorCallback should be implemented in the user file
2441 /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes
2442 and user can use HAL_SPI_GetError() API to check the latest error occurred
2447 * @brief SPI Abort Complete callback.
2448 * @param hspi SPI handle.
2449 * @retval None
2451 __weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi)
2453 /* Prevent unused argument(s) compilation warning */
2454 UNUSED(hspi);
2456 /* NOTE : This function should not be modified, when the callback is needed,
2457 the HAL_SPI_AbortCpltCallback can be implemented in the user file.
2462 * @}
2465 /** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions
2466 * @brief SPI control functions
2468 @verbatim
2469 ===============================================================================
2470 ##### Peripheral State and Errors functions #####
2471 ===============================================================================
2472 [..]
2473 This subsection provides a set of functions allowing to control the SPI.
2474 (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral
2475 (+) HAL_SPI_GetError() check in run-time Errors occurring during communication
2476 @endverbatim
2477 * @{
2481 * @brief Return the SPI handle state.
2482 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2483 * the configuration information for SPI module.
2484 * @retval SPI state
2486 HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi)
2488 /* Return SPI handle state */
2489 return hspi->State;
2493 * @brief Return the SPI error code.
2494 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2495 * the configuration information for SPI module.
2496 * @retval SPI error code in bitmap format
2498 uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi)
2500 /* Return SPI ErrorCode */
2501 return hspi->ErrorCode;
2505 * @}
2509 * @}
2512 /** @addtogroup SPI_Private_Functions
2513 * @brief Private functions
2514 * @{
2518 * @brief DMA SPI transmit process complete callback.
2519 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2520 * the configuration information for the specified DMA module.
2521 * @retval None
2523 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma)
2525 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2526 uint32_t tickstart = 0U;
2528 /* Init tickstart for timeout managment*/
2529 tickstart = HAL_GetTick();
2531 /* DMA Normal Mode */
2532 if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC)
2534 /* Disable ERR interrupt */
2535 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2537 /* Disable Tx DMA Request */
2538 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
2540 /* Check the end of the transaction */
2541 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2543 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2546 /* Clear overrun flag in 2 Lines communication mode because received data is not read */
2547 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
2549 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2552 hspi->TxXferCount = 0U;
2553 hspi->State = HAL_SPI_STATE_READY;
2555 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2557 HAL_SPI_ErrorCallback(hspi);
2558 return;
2561 HAL_SPI_TxCpltCallback(hspi);
2565 * @brief DMA SPI receive process complete callback.
2566 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2567 * the configuration information for the specified DMA module.
2568 * @retval None
2570 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
2572 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2573 uint32_t tickstart = 0U;
2574 #if (USE_SPI_CRC != 0U)
2575 __IO uint16_t tmpreg = 0U;
2576 #endif /* USE_SPI_CRC */
2578 /* Init tickstart for timeout management*/
2579 tickstart = HAL_GetTick();
2581 /* DMA Normal Mode */
2582 if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC)
2584 /* Disable ERR interrupt */
2585 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2587 #if (USE_SPI_CRC != 0U)
2588 /* CRC handling */
2589 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2591 /* Wait until RXNE flag */
2592 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2594 /* Error on the CRC reception */
2595 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2597 /* Read CRC */
2598 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
2600 tmpreg = hspi->Instance->DR;
2601 /* To avoid GCC warning */
2602 UNUSED(tmpreg);
2604 else
2606 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2607 /* To avoid GCC warning */
2608 UNUSED(tmpreg);
2610 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
2612 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2614 /* Error on the CRC reception */
2615 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2617 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2618 /* To avoid GCC warning */
2619 UNUSED(tmpreg);
2623 #endif /* USE_SPI_CRC */
2625 /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */
2626 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2628 /* Check the end of the transaction */
2629 if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2631 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
2634 hspi->RxXferCount = 0U;
2635 hspi->State = HAL_SPI_STATE_READY;
2637 #if (USE_SPI_CRC != 0U)
2638 /* Check if CRC error occurred */
2639 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2641 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2642 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2644 #endif /* USE_SPI_CRC */
2646 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2648 HAL_SPI_ErrorCallback(hspi);
2649 return;
2652 HAL_SPI_RxCpltCallback(hspi);
2656 * @brief DMA SPI transmit receive process complete callback.
2657 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2658 * the configuration information for the specified DMA module.
2659 * @retval None
2661 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2663 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2664 uint32_t tickstart = 0U;
2665 #if (USE_SPI_CRC != 0U)
2666 __IO int16_t tmpreg = 0U;
2667 #endif /* USE_SPI_CRC */
2668 /* Init tickstart for timeout management*/
2669 tickstart = HAL_GetTick();
2671 /* DMA Normal Mode */
2672 if ((hdma->Instance->CR & DMA_SxCR_CIRC) != DMA_SxCR_CIRC)
2674 /* Disable ERR interrupt */
2675 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2677 #if (USE_SPI_CRC != 0U)
2678 /* CRC handling */
2679 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2681 if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_8BIT))
2683 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_QUARTER_FULL, SPI_DEFAULT_TIMEOUT,
2684 tickstart) != HAL_OK)
2686 /* Error on the CRC reception */
2687 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2689 /* Read CRC to Flush DR and RXNE flag */
2690 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2691 /* To avoid GCC warning */
2692 UNUSED(tmpreg);
2694 else
2696 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_HALF_FULL, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2698 /* Error on the CRC reception */
2699 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2701 /* Read CRC to Flush DR and RXNE flag */
2702 tmpreg = hspi->Instance->DR;
2703 /* To avoid GCC warning */
2704 UNUSED(tmpreg);
2707 #endif /* USE_SPI_CRC */
2709 /* Check the end of the transaction */
2710 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2712 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2715 /* Disable Rx/Tx DMA Request */
2716 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2718 hspi->TxXferCount = 0U;
2719 hspi->RxXferCount = 0U;
2720 hspi->State = HAL_SPI_STATE_READY;
2722 #if (USE_SPI_CRC != 0U)
2723 /* Check if CRC error occurred */
2724 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2726 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2727 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2729 #endif /* USE_SPI_CRC */
2731 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2733 HAL_SPI_ErrorCallback(hspi);
2734 return;
2737 HAL_SPI_TxRxCpltCallback(hspi);
2741 * @brief DMA SPI half transmit process complete callback.
2742 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2743 * the configuration information for the specified DMA module.
2744 * @retval None
2746 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma)
2748 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2750 HAL_SPI_TxHalfCpltCallback(hspi);
2754 * @brief DMA SPI half receive process complete callback
2755 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2756 * the configuration information for the specified DMA module.
2757 * @retval None
2759 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma)
2761 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2763 HAL_SPI_RxHalfCpltCallback(hspi);
2767 * @brief DMA SPI half transmit receive process complete callback.
2768 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2769 * the configuration information for the specified DMA module.
2770 * @retval None
2772 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2774 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2776 HAL_SPI_TxRxHalfCpltCallback(hspi);
2780 * @brief DMA SPI communication error callback.
2781 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2782 * the configuration information for the specified DMA module.
2783 * @retval None
2785 static void SPI_DMAError(DMA_HandleTypeDef *hdma)
2787 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2789 /* Stop the disable DMA transfer on SPI side */
2790 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2792 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
2793 hspi->State = HAL_SPI_STATE_READY;
2794 HAL_SPI_ErrorCallback(hspi);
2798 * @brief DMA SPI communication abort callback, when initiated by HAL services on Error
2799 * (To be called at end of DMA Abort procedure following error occurrence).
2800 * @param hdma DMA handle.
2801 * @retval None
2803 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma)
2805 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2806 hspi->RxXferCount = 0U;
2807 hspi->TxXferCount = 0U;
2809 HAL_SPI_ErrorCallback(hspi);
2813 * @brief DMA SPI Tx communication abort callback, when initiated by user
2814 * (To be called at end of DMA Tx Abort procedure following user abort request).
2815 * @note When this callback is executed, User Abort complete call back is called only if no
2816 * Abort still ongoing for Rx DMA Handle.
2817 * @param hdma DMA handle.
2818 * @retval None
2820 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
2822 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2824 hspi->hdmatx->XferAbortCallback = NULL;
2826 /* Disable Tx DMA Request */
2827 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
2829 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2831 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2834 /* Disable SPI Peripheral */
2835 __HAL_SPI_DISABLE(hspi);
2837 /* Empty the FRLVL fifo */
2838 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2840 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2843 /* Check if an Abort process is still ongoing */
2844 if (hspi->hdmarx != NULL)
2846 if (hspi->hdmarx->XferAbortCallback != NULL)
2848 return;
2852 /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
2853 hspi->RxXferCount = 0U;
2854 hspi->TxXferCount = 0U;
2856 /* Check no error during Abort procedure */
2857 if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
2859 /* Reset errorCode */
2860 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2863 /* Clear the Error flags in the SR register */
2864 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2865 __HAL_SPI_CLEAR_FREFLAG(hspi);
2867 /* Restore hspi->State to Ready */
2868 hspi->State = HAL_SPI_STATE_READY;
2870 /* Call user Abort complete callback */
2871 HAL_SPI_AbortCpltCallback(hspi);
2875 * @brief DMA SPI Rx communication abort callback, when initiated by user
2876 * (To be called at end of DMA Rx Abort procedure following user abort request).
2877 * @note When this callback is executed, User Abort complete call back is called only if no
2878 * Abort still ongoing for Tx DMA Handle.
2879 * @param hdma DMA handle.
2880 * @retval None
2882 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
2884 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2886 /* Disable SPI Peripheral */
2887 __HAL_SPI_DISABLE(hspi);
2889 hspi->hdmarx->XferAbortCallback = NULL;
2891 /* Disable Rx DMA Request */
2892 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
2894 /* Control the BSY flag */
2895 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2897 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2900 /* Empty the FRLVL fifo */
2901 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2903 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2906 /* Check if an Abort process is still ongoing */
2907 if (hspi->hdmatx != NULL)
2909 if (hspi->hdmatx->XferAbortCallback != NULL)
2911 return;
2915 /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
2916 hspi->RxXferCount = 0U;
2917 hspi->TxXferCount = 0U;
2919 /* Check no error during Abort procedure */
2920 if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
2922 /* Reset errorCode */
2923 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2926 /* Clear the Error flags in the SR register */
2927 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2928 __HAL_SPI_CLEAR_FREFLAG(hspi);
2930 /* Restore hspi->State to Ready */
2931 hspi->State = HAL_SPI_STATE_READY;
2933 /* Call user Abort complete callback */
2934 HAL_SPI_AbortCpltCallback(hspi);
2938 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
2939 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2940 * the configuration information for SPI module.
2941 * @retval None
2943 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
2945 /* Receive data in packing mode */
2946 if (hspi->RxXferCount > 1U)
2948 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
2949 hspi->pRxBuffPtr += sizeof(uint16_t);
2950 hspi->RxXferCount -= 2U;
2951 if (hspi->RxXferCount == 1U)
2953 /* set fiforxthreshold according the reception data length: 8bit */
2954 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
2957 /* Receive data in 8 Bit mode */
2958 else
2960 *hspi->pRxBuffPtr++ = *((__IO uint8_t *)&hspi->Instance->DR);
2961 hspi->RxXferCount--;
2964 /* check end of the reception */
2965 if (hspi->RxXferCount == 0U)
2967 #if (USE_SPI_CRC != 0U)
2968 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2970 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
2971 hspi->RxISR = SPI_2linesRxISR_8BITCRC;
2972 return;
2974 #endif /* USE_SPI_CRC */
2976 /* Disable RXNE and ERR interrupt */
2977 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
2979 if (hspi->TxXferCount == 0U)
2981 SPI_CloseRxTx_ISR(hspi);
2986 #if (USE_SPI_CRC != 0U)
2988 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
2989 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2990 * the configuration information for SPI module.
2991 * @retval None
2993 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
2995 __IO uint8_t tmpreg = 0U;
2997 /* Read data register to flush CRC */
2998 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3000 /* To avoid GCC warning */
3001 UNUSED(tmpreg);
3003 hspi->CRCSize--;
3005 /* check end of the reception */
3006 if (hspi->CRCSize == 0U)
3008 /* Disable RXNE and ERR interrupt */
3009 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3011 if (hspi->TxXferCount == 0U)
3013 SPI_CloseRxTx_ISR(hspi);
3017 #endif /* USE_SPI_CRC */
3020 * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode.
3021 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3022 * the configuration information for SPI module.
3023 * @retval None
3025 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3027 /* Transmit data in packing Bit mode */
3028 if (hspi->TxXferCount >= 2U)
3030 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3031 hspi->pTxBuffPtr += sizeof(uint16_t);
3032 hspi->TxXferCount -= 2U;
3034 /* Transmit data in 8 Bit mode */
3035 else
3037 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
3038 hspi->TxXferCount--;
3041 /* check the end of the transmission */
3042 if (hspi->TxXferCount == 0U)
3044 #if (USE_SPI_CRC != 0U)
3045 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3047 /* Set CRC Next Bit to send CRC */
3048 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3049 /* Disable TXE interrupt */
3050 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3051 return;
3053 #endif /* USE_SPI_CRC */
3055 /* Disable TXE interrupt */
3056 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3058 if (hspi->RxXferCount == 0U)
3060 SPI_CloseRxTx_ISR(hspi);
3066 * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode.
3067 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3068 * the configuration information for SPI module.
3069 * @retval None
3071 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3073 /* Receive data in 16 Bit mode */
3074 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
3075 hspi->pRxBuffPtr += sizeof(uint16_t);
3076 hspi->RxXferCount--;
3078 if (hspi->RxXferCount == 0U)
3080 #if (USE_SPI_CRC != 0U)
3081 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3083 hspi->RxISR = SPI_2linesRxISR_16BITCRC;
3084 return;
3086 #endif /* USE_SPI_CRC */
3088 /* Disable RXNE interrupt */
3089 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
3091 if (hspi->TxXferCount == 0U)
3093 SPI_CloseRxTx_ISR(hspi);
3098 #if (USE_SPI_CRC != 0U)
3100 * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode.
3101 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3102 * the configuration information for SPI module.
3103 * @retval None
3105 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
3107 /* Receive data in 16 Bit mode */
3108 __IO uint16_t tmpreg = 0U;
3110 /* Read data register to flush CRC */
3111 tmpreg = hspi->Instance->DR;
3113 /* To avoid GCC warning */
3114 UNUSED(tmpreg);
3116 /* Disable RXNE interrupt */
3117 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
3119 SPI_CloseRxTx_ISR(hspi);
3121 #endif /* USE_SPI_CRC */
3124 * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode.
3125 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3126 * the configuration information for SPI module.
3127 * @retval None
3129 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3131 /* Transmit data in 16 Bit mode */
3132 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3133 hspi->pTxBuffPtr += sizeof(uint16_t);
3134 hspi->TxXferCount--;
3136 /* Enable CRC Transmission */
3137 if (hspi->TxXferCount == 0U)
3139 #if (USE_SPI_CRC != 0U)
3140 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3142 /* Set CRC Next Bit to send CRC */
3143 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3144 /* Disable TXE interrupt */
3145 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3146 return;
3148 #endif /* USE_SPI_CRC */
3150 /* Disable TXE interrupt */
3151 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3153 if (hspi->RxXferCount == 0U)
3155 SPI_CloseRxTx_ISR(hspi);
3160 #if (USE_SPI_CRC != 0U)
3162 * @brief Manage the CRC 8-bit receive in Interrupt context.
3163 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3164 * the configuration information for SPI module.
3165 * @retval None
3167 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
3169 __IO uint8_t tmpreg = 0U;
3171 /* Read data register to flush CRC */
3172 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3174 /* To avoid GCC warning */
3175 UNUSED(tmpreg);
3177 hspi->CRCSize--;
3179 if (hspi->CRCSize == 0U)
3181 SPI_CloseRx_ISR(hspi);
3184 #endif /* USE_SPI_CRC */
3187 * @brief Manage the receive 8-bit in Interrupt context.
3188 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3189 * the configuration information for SPI module.
3190 * @retval None
3192 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3194 *hspi->pRxBuffPtr++ = (*(__IO uint8_t *)&hspi->Instance->DR);
3195 hspi->RxXferCount--;
3197 #if (USE_SPI_CRC != 0U)
3198 /* Enable CRC Transmission */
3199 if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
3201 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3203 #endif /* USE_SPI_CRC */
3205 if (hspi->RxXferCount == 0U)
3207 #if (USE_SPI_CRC != 0U)
3208 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3210 hspi->RxISR = SPI_RxISR_8BITCRC;
3211 return;
3213 #endif /* USE_SPI_CRC */
3214 SPI_CloseRx_ISR(hspi);
3218 #if (USE_SPI_CRC != 0U)
3220 * @brief Manage the CRC 16-bit receive in Interrupt context.
3221 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3222 * the configuration information for SPI module.
3223 * @retval None
3225 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
3227 __IO uint16_t tmpreg = 0U;
3229 /* Read data register to flush CRC */
3230 tmpreg = hspi->Instance->DR;
3232 /* To avoid GCC warning */
3233 UNUSED(tmpreg);
3235 /* Disable RXNE and ERR interrupt */
3236 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3238 SPI_CloseRx_ISR(hspi);
3240 #endif /* USE_SPI_CRC */
3243 * @brief Manage the 16-bit receive in Interrupt context.
3244 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3245 * the configuration information for SPI module.
3246 * @retval None
3248 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3250 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
3251 hspi->pRxBuffPtr += sizeof(uint16_t);
3252 hspi->RxXferCount--;
3254 #if (USE_SPI_CRC != 0U)
3255 /* Enable CRC Transmission */
3256 if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
3258 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3260 #endif /* USE_SPI_CRC */
3262 if (hspi->RxXferCount == 0U)
3264 #if (USE_SPI_CRC != 0U)
3265 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3267 hspi->RxISR = SPI_RxISR_16BITCRC;
3268 return;
3270 #endif /* USE_SPI_CRC */
3271 SPI_CloseRx_ISR(hspi);
3276 * @brief Handle the data 8-bit transmit in Interrupt mode.
3277 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3278 * the configuration information for SPI module.
3279 * @retval None
3281 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3283 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
3284 hspi->TxXferCount--;
3286 if (hspi->TxXferCount == 0U)
3288 #if (USE_SPI_CRC != 0U)
3289 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3291 /* Enable CRC Transmission */
3292 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3294 #endif /* USE_SPI_CRC */
3295 SPI_CloseTx_ISR(hspi);
3300 * @brief Handle the data 16-bit transmit in Interrupt mode.
3301 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3302 * the configuration information for SPI module.
3303 * @retval None
3305 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3307 /* Transmit data in 16 Bit mode */
3308 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3309 hspi->pTxBuffPtr += sizeof(uint16_t);
3310 hspi->TxXferCount--;
3312 if (hspi->TxXferCount == 0U)
3314 #if (USE_SPI_CRC != 0U)
3315 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3317 /* Enable CRC Transmission */
3318 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3320 #endif /* USE_SPI_CRC */
3321 SPI_CloseTx_ISR(hspi);
3326 * @brief Handle SPI Communication Timeout.
3327 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3328 * the configuration information for SPI module.
3329 * @param Flag: SPI flag to check
3330 * @param State: flag state to check
3331 * @param Timeout: Timeout duration
3332 * @param Tickstart: tick start value
3333 * @retval HAL status
3335 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State,
3336 uint32_t Timeout, uint32_t Tickstart)
3338 while ((hspi->Instance->SR & Flag) != State)
3340 if (Timeout != HAL_MAX_DELAY)
3342 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) >= Timeout))
3344 /* Disable the SPI and reset the CRC: the CRC value should be cleared
3345 on both master and slave sides in order to resynchronize the master
3346 and slave for their respective CRC calculation */
3348 /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
3349 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
3351 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3352 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3354 /* Disable SPI peripheral */
3355 __HAL_SPI_DISABLE(hspi);
3358 /* Reset CRC Calculation */
3359 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3361 SPI_RESET_CRC(hspi);
3364 hspi->State = HAL_SPI_STATE_READY;
3366 /* Process Unlocked */
3367 __HAL_UNLOCK(hspi);
3369 return HAL_TIMEOUT;
3374 return HAL_OK;
3378 * @brief Handle SPI FIFO Communication Timeout.
3379 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3380 * the configuration information for SPI module.
3381 * @param Fifo: Fifo to check
3382 * @param State: Fifo state to check
3383 * @param Timeout: Timeout duration
3384 * @param Tickstart: tick start value
3385 * @retval HAL status
3387 static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
3388 uint32_t Timeout, uint32_t Tickstart)
3390 __IO uint8_t tmpreg;
3392 while ((hspi->Instance->SR & Fifo) != State)
3394 if ((Fifo == SPI_SR_FRLVL) && (State == SPI_FRLVL_EMPTY))
3396 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3397 /* To avoid GCC warning */
3398 UNUSED(tmpreg);
3401 if (Timeout != HAL_MAX_DELAY)
3403 if ((Timeout == 0) || ((HAL_GetTick() - Tickstart) >= Timeout))
3405 /* Disable the SPI and reset the CRC: the CRC value should be cleared
3406 on both master and slave sides in order to resynchronize the master
3407 and slave for their respective CRC calculation */
3409 /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
3410 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
3412 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3413 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3415 /* Disable SPI peripheral */
3416 __HAL_SPI_DISABLE(hspi);
3419 /* Reset CRC Calculation */
3420 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3422 SPI_RESET_CRC(hspi);
3425 hspi->State = HAL_SPI_STATE_READY;
3427 /* Process Unlocked */
3428 __HAL_UNLOCK(hspi);
3430 return HAL_TIMEOUT;
3435 return HAL_OK;
3439 * @brief Handle the check of the RX transaction complete.
3440 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3441 * the configuration information for SPI module.
3442 * @param Timeout: Timeout duration
3443 * @param Tickstart: tick start value
3444 * @retval None.
3446 static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
3448 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3449 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3451 /* Disable SPI peripheral */
3452 __HAL_SPI_DISABLE(hspi);
3455 /* Control the BSY flag */
3456 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
3458 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3459 return HAL_TIMEOUT;
3462 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3463 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3465 /* Empty the FRLVL fifo */
3466 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3468 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3469 return HAL_TIMEOUT;
3472 return HAL_OK;
3476 * @brief Handle the check of the RXTX or TX transaction complete.
3477 * @param hspi: SPI handle
3478 * @param Timeout: Timeout duration
3479 * @param Tickstart: tick start value
3481 static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
3483 /* Control if the TX fifo is empty */
3484 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FTLVL, SPI_FTLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3486 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3487 return HAL_TIMEOUT;
3489 /* Control the BSY flag */
3490 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
3492 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3493 return HAL_TIMEOUT;
3495 /* Control if the RX fifo is empty */
3496 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3498 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3499 return HAL_TIMEOUT;
3501 return HAL_OK;
3505 * @brief Handle the end of the RXTX transaction.
3506 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3507 * the configuration information for SPI module.
3508 * @retval None
3510 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi)
3512 uint32_t tickstart = 0U;
3514 /* Init tickstart for timeout managment*/
3515 tickstart = HAL_GetTick();
3517 /* Disable ERR interrupt */
3518 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
3520 /* Check the end of the transaction */
3521 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
3523 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3526 #if (USE_SPI_CRC != 0U)
3527 /* Check if CRC error occurred */
3528 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3530 hspi->State = HAL_SPI_STATE_READY;
3531 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3532 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3533 HAL_SPI_ErrorCallback(hspi);
3535 else
3537 #endif /* USE_SPI_CRC */
3538 if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3540 if (hspi->State == HAL_SPI_STATE_BUSY_RX)
3542 hspi->State = HAL_SPI_STATE_READY;
3543 HAL_SPI_RxCpltCallback(hspi);
3545 else
3547 hspi->State = HAL_SPI_STATE_READY;
3548 HAL_SPI_TxRxCpltCallback(hspi);
3551 else
3553 hspi->State = HAL_SPI_STATE_READY;
3554 HAL_SPI_ErrorCallback(hspi);
3556 #if (USE_SPI_CRC != 0U)
3558 #endif /* USE_SPI_CRC */
3562 * @brief Handle the end of the RX transaction.
3563 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3564 * the configuration information for SPI module.
3565 * @retval None
3567 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi)
3569 /* Disable RXNE and ERR interrupt */
3570 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3572 /* Check the end of the transaction */
3573 if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3575 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3577 hspi->State = HAL_SPI_STATE_READY;
3579 #if (USE_SPI_CRC != 0U)
3580 /* Check if CRC error occurred */
3581 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3583 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3584 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3585 HAL_SPI_ErrorCallback(hspi);
3587 else
3589 #endif /* USE_SPI_CRC */
3590 if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3592 HAL_SPI_RxCpltCallback(hspi);
3594 else
3596 HAL_SPI_ErrorCallback(hspi);
3598 #if (USE_SPI_CRC != 0U)
3600 #endif /* USE_SPI_CRC */
3604 * @brief Handle the end of the TX transaction.
3605 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3606 * the configuration information for SPI module.
3607 * @retval None
3609 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi)
3611 uint32_t tickstart = 0U;
3613 /* Init tickstart for timeout management*/
3614 tickstart = HAL_GetTick();
3616 /* Disable TXE and ERR interrupt */
3617 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
3619 /* Check the end of the transaction */
3620 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
3622 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3625 /* Clear overrun flag in 2 Lines communication mode because received is not read */
3626 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
3628 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3631 hspi->State = HAL_SPI_STATE_READY;
3632 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
3634 HAL_SPI_ErrorCallback(hspi);
3636 else
3638 HAL_SPI_TxCpltCallback(hspi);
3643 * @brief Handle abort a Rx transaction.
3644 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3645 * the configuration information for SPI module.
3646 * @retval None
3648 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi)
3650 uint32_t tickstart = 0U;
3652 /* Init tickstart for timeout managment*/
3653 tickstart = HAL_GetTick();
3655 /* Disable SPI Peripheral */
3656 __HAL_SPI_DISABLE(hspi);
3658 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3659 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3661 while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
3663 if ((HAL_GetTick() - tickstart) >= HAL_MAX_DELAY)
3665 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3669 /* Control the BSY flag */
3670 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3672 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3675 /* Empty the FRLVL fifo */
3676 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3678 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3681 hspi->State = HAL_SPI_STATE_ABORT;
3685 * @brief Handle abort a Tx or Rx/Tx transaction.
3686 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3687 * the configuration information for SPI module.
3688 * @retval None
3690 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi)
3692 uint32_t tickstart = 0U;
3694 /* Init tickstart for timeout managment*/
3695 tickstart = HAL_GetTick();
3697 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3698 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3700 while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
3702 if ((HAL_GetTick() - tickstart) >= HAL_MAX_DELAY)
3704 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3708 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3710 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3713 /* Disable SPI Peripheral */
3714 __HAL_SPI_DISABLE(hspi);
3716 /* Empty the FRLVL fifo */
3717 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3719 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3722 hspi->State = HAL_SPI_STATE_ABORT;
3726 * @}
3729 #endif /* HAL_SPI_MODULE_ENABLED */
3732 * @}
3736 * @}
3739 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/