Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_spi.c
blobb568ac8263d48043d15539ae89d5c4d46ea62a9a
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_spi.c
4 * @author MCD Application Team
5 * @brief SPI HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Serial Peripheral Interface (SPI) peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral Control functions
11 * + Peripheral State functions
13 @verbatim
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
17 [..]
18 The SPI HAL driver can be used as follows:
20 (#) Declare a SPI_HandleTypeDef handle structure, for example:
21 SPI_HandleTypeDef hspi;
23 (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API:
24 (##) Enable the SPIx interface clock
25 (##) SPI pins configuration
26 (+++) Enable the clock for the SPI GPIOs
27 (+++) Configure these SPI pins as alternate function push-pull
28 (##) NVIC configuration if you need to use interrupt process
29 (+++) Configure the SPIx interrupt priority
30 (+++) Enable the NVIC SPI IRQ handle
31 (##) DMA Configuration if you need to use DMA process
32 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel
33 (+++) Enable the DMAx clock
34 (+++) Configure the DMA handle parameters
35 (+++) Configure the DMA Tx or Rx Stream/Channel
36 (+++) Associate the initialized hdma_tx handle to the hspi DMA Tx or Rx handle
37 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel
39 (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS
40 management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure.
42 (#) Initialize the SPI registers by calling the HAL_SPI_Init() API:
43 (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
44 by calling the customized HAL_SPI_MspInit() API.
45 [..]
46 Circular mode restriction:
47 (#) The DMA circular mode cannot be used when the SPI is configured in these modes:
48 (##) Master 2Lines RxOnly
49 (##) Master 1Line Rx
50 (#) The CRC feature is not managed when the DMA circular mode is enabled
51 (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs
52 the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks
53 [..]
54 Master Receive mode restriction:
55 (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=0) or
56 bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI
57 does not initiate a new transfer the following procedure has to be respected:
58 (##) HAL_SPI_DeInit()
59 (##) HAL_SPI_Init()
60 [..]
61 The HAL drivers do not allow reaching all supported SPI frequencies in the different SPI
62 modes. Refer to the source code (stm32xxxx_hal_spi.c header) to get a summary of the
63 maximum SPI frequency that can be reached with a data size of 8 or 16 bits, depending on
64 the APBx peripheral clock frequency (fPCLK) used by the SPI instance.
67 @endverbatim
69 Additional table :
71 DataSize = SPI_DATASIZE_8BIT:
72 +----------------------------------------------------------------------------------------------+
73 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
74 | Process | Tranfert mode |---------------------|----------------------|----------------------|
75 | | | Master | Slave | Master | Slave | Master | Slave |
76 |==============================================================================================|
77 | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
78 | X |----------------|----------|----------|-----------|----------|-----------|----------|
79 | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
80 | R |----------------|----------|----------|-----------|----------|-----------|----------|
81 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
82 |=========|================|==========|==========|===========|==========|===========|==========|
83 | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
84 | |----------------|----------|----------|-----------|----------|-----------|----------|
85 | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
86 | X |----------------|----------|----------|-----------|----------|-----------|----------|
87 | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
88 |=========|================|==========|==========|===========|==========|===========|==========|
89 | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
90 | |----------------|----------|----------|-----------|----------|-----------|----------|
91 | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
92 | X |----------------|----------|----------|-----------|----------|-----------|----------|
93 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
94 +----------------------------------------------------------------------------------------------+
96 DataSize = SPI_DATASIZE_16BIT:
97 +----------------------------------------------------------------------------------------------+
98 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
99 | Process | Tranfert mode |---------------------|----------------------|----------------------|
100 | | | Master | Slave | Master | Slave | Master | Slave |
101 |==============================================================================================|
102 | T | Polling | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
103 | X |----------------|----------|----------|-----------|----------|-----------|----------|
104 | / | Interrupt | Fpclk/4 | Fpclk/16 | NA | NA | NA | NA |
105 | R |----------------|----------|----------|-----------|----------|-----------|----------|
106 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
107 |=========|================|==========|==========|===========|==========|===========|==========|
108 | | Polling | Fpclk/4 | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 |
109 | |----------------|----------|----------|-----------|----------|-----------|----------|
110 | R | Interrupt | Fpclk/8 | Fpclk/16 | Fpclk/8 | Fpclk/8 | Fpclk/8 | Fpclk/4 |
111 | X |----------------|----------|----------|-----------|----------|-----------|----------|
112 | | DMA | Fpclk/4 | Fpclk/2 | Fpclk/2 | Fpclk/16 | Fpclk/2 | Fpclk/16 |
113 |=========|================|==========|==========|===========|==========|===========|==========|
114 | | Polling | Fpclk/8 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/8 |
115 | |----------------|----------|----------|-----------|----------|-----------|----------|
116 | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/16 | Fpclk/8 |
117 | X |----------------|----------|----------|-----------|----------|-----------|----------|
118 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/8 | Fpclk/16 |
119 +----------------------------------------------------------------------------------------------+
120 @note The max SPI frequency depend on SPI data size (4bits, 5bits,..., 8bits,...15bits, 16bits),
121 SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA).
122 @note
123 (#) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA()
124 (#) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA()
125 (#) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA()
127 ******************************************************************************
128 * @attention
130 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
132 * Redistribution and use in source and binary forms, with or without modification,
133 * are permitted provided that the following conditions are met:
134 * 1. Redistributions of source code must retain the above copyright notice,
135 * this list of conditions and the following disclaimer.
136 * 2. Redistributions in binary form must reproduce the above copyright notice,
137 * this list of conditions and the following disclaimer in the documentation
138 * and/or other materials provided with the distribution.
139 * 3. Neither the name of STMicroelectronics nor the names of its contributors
140 * may be used to endorse or promote products derived from this software
141 * without specific prior written permission.
143 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
144 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
145 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
146 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
147 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
148 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
149 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
150 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
151 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
152 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
154 ******************************************************************************
157 /* Includes ------------------------------------------------------------------*/
158 #include "stm32f3xx_hal.h"
160 /** @addtogroup STM32F3xx_HAL_Driver
161 * @{
164 /** @defgroup SPI SPI
165 * @brief SPI HAL module driver
166 * @{
168 #ifdef HAL_SPI_MODULE_ENABLED
170 /* Private typedef -----------------------------------------------------------*/
171 /* Private defines -----------------------------------------------------------*/
172 /** @defgroup SPI_Private_Constants SPI Private Constants
173 * @{
175 #define SPI_DEFAULT_TIMEOUT 100U
177 * @}
180 /* Private macros ------------------------------------------------------------*/
181 /* Private variables ---------------------------------------------------------*/
182 /* Private function prototypes -----------------------------------------------*/
183 /** @defgroup SPI_Private_Functions SPI Private Functions
184 * @{
186 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma);
187 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
188 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma);
189 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma);
190 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma);
191 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma);
192 static void SPI_DMAError(DMA_HandleTypeDef *hdma);
193 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma);
194 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
195 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
196 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State,
197 uint32_t Timeout, uint32_t Tickstart);
198 static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
199 uint32_t Timeout, uint32_t Tickstart);
200 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
201 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
202 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
203 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
204 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
205 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
206 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
207 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
208 #if (USE_SPI_CRC != 0U)
209 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
210 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
211 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
212 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
213 #endif /* USE_SPI_CRC */
214 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi);
215 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi);
216 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi);
217 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi);
218 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi);
219 static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
220 static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
222 * @}
225 /* Exported functions --------------------------------------------------------*/
226 /** @defgroup SPI_Exported_Functions SPI Exported Functions
227 * @{
230 /** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions
231 * @brief Initialization and Configuration functions
233 @verbatim
234 ===============================================================================
235 ##### Initialization and de-initialization functions #####
236 ===============================================================================
237 [..] This subsection provides a set of functions allowing to initialize and
238 de-initialize the SPIx peripheral:
240 (+) User must implement HAL_SPI_MspInit() function in which he configures
241 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
243 (+) Call the function HAL_SPI_Init() to configure the selected device with
244 the selected configuration:
245 (++) Mode
246 (++) Direction
247 (++) Data Size
248 (++) Clock Polarity and Phase
249 (++) NSS Management
250 (++) BaudRate Prescaler
251 (++) FirstBit
252 (++) TIMode
253 (++) CRC Calculation
254 (++) CRC Polynomial if CRC enabled
255 (++) CRC Length, used only with Data8 and Data16
256 (++) FIFO reception threshold
258 (+) Call the function HAL_SPI_DeInit() to restore the default configuration
259 of the selected SPIx peripheral.
261 @endverbatim
262 * @{
266 * @brief Initialize the SPI according to the specified parameters
267 * in the SPI_InitTypeDef and initialize the associated handle.
268 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
269 * the configuration information for SPI module.
270 * @retval HAL status
272 HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi)
274 uint32_t frxth;
276 /* Check the SPI handle allocation */
277 if (hspi == NULL)
279 return HAL_ERROR;
282 /* Check the parameters */
283 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
284 assert_param(IS_SPI_MODE(hspi->Init.Mode));
285 assert_param(IS_SPI_DIRECTION(hspi->Init.Direction));
286 assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize));
287 assert_param(IS_SPI_NSS(hspi->Init.NSS));
288 assert_param(IS_SPI_NSSP(hspi->Init.NSSPMode));
289 assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
290 assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit));
291 assert_param(IS_SPI_TIMODE(hspi->Init.TIMode));
292 if (hspi->Init.TIMode == SPI_TIMODE_DISABLE)
294 assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity));
295 assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase));
297 #if (USE_SPI_CRC != 0U)
298 assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation));
299 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
301 assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial));
302 assert_param(IS_SPI_CRC_LENGTH(hspi->Init.CRCLength));
304 #else
305 hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
306 #endif /* USE_SPI_CRC */
308 if (hspi->State == HAL_SPI_STATE_RESET)
310 /* Allocate lock resource and initialize it */
311 hspi->Lock = HAL_UNLOCKED;
313 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
314 HAL_SPI_MspInit(hspi);
317 hspi->State = HAL_SPI_STATE_BUSY;
319 /* Disable the selected SPI peripheral */
320 __HAL_SPI_DISABLE(hspi);
322 /* Align by default the rs fifo threshold on the data size */
323 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
325 frxth = SPI_RXFIFO_THRESHOLD_HF;
327 else
329 frxth = SPI_RXFIFO_THRESHOLD_QF;
332 /* CRC calculation is valid only for 16Bit and 8 Bit */
333 if ((hspi->Init.DataSize != SPI_DATASIZE_16BIT) && (hspi->Init.DataSize != SPI_DATASIZE_8BIT))
335 /* CRC must be disabled */
336 hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
339 /* Align the CRC Length on the data size */
340 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_DATASIZE)
342 /* CRC Length aligned on the data size : value set by default */
343 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
345 hspi->Init.CRCLength = SPI_CRC_LENGTH_16BIT;
347 else
349 hspi->Init.CRCLength = SPI_CRC_LENGTH_8BIT;
353 /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/
354 /* Configure : SPI Mode, Communication Mode, Clock polarity and phase, NSS management,
355 Communication speed, First bit and CRC calculation state */
356 WRITE_REG(hspi->Instance->CR1, (hspi->Init.Mode | hspi->Init.Direction |
357 hspi->Init.CLKPolarity | hspi->Init.CLKPhase | (hspi->Init.NSS & SPI_CR1_SSM) |
358 hspi->Init.BaudRatePrescaler | hspi->Init.FirstBit | hspi->Init.CRCCalculation));
359 #if (USE_SPI_CRC != 0U)
360 /* Configure : CRC Length */
361 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
363 hspi->Instance->CR1 |= SPI_CR1_CRCL;
365 #endif /* USE_SPI_CRC */
367 /* Configure : NSS management, TI Mode, NSS Pulse, Data size and Rx Fifo Threshold */
368 WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | hspi->Init.TIMode |
369 hspi->Init.NSSPMode | hspi->Init.DataSize) | frxth);
371 #if (USE_SPI_CRC != 0U)
372 /*---------------------------- SPIx CRCPOLY Configuration ------------------*/
373 /* Configure : CRC Polynomial */
374 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
376 WRITE_REG(hspi->Instance->CRCPR, hspi->Init.CRCPolynomial);
378 #endif /* USE_SPI_CRC */
380 #if defined(SPI_I2SCFGR_I2SMOD)
381 /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */
382 CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD);
383 #endif /* SPI_I2SCFGR_I2SMOD */
385 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
386 hspi->State = HAL_SPI_STATE_READY;
388 return HAL_OK;
392 * @brief De-Initialize the SPI peripheral.
393 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
394 * the configuration information for SPI module.
395 * @retval HAL status
397 HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi)
399 /* Check the SPI handle allocation */
400 if (hspi == NULL)
402 return HAL_ERROR;
405 /* Check SPI Instance parameter */
406 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
408 hspi->State = HAL_SPI_STATE_BUSY;
410 /* Disable the SPI Peripheral Clock */
411 __HAL_SPI_DISABLE(hspi);
413 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
414 HAL_SPI_MspDeInit(hspi);
416 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
417 hspi->State = HAL_SPI_STATE_RESET;
419 /* Release Lock */
420 __HAL_UNLOCK(hspi);
422 return HAL_OK;
426 * @brief Initialize the SPI MSP.
427 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
428 * the configuration information for SPI module.
429 * @retval None
431 __weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
433 /* Prevent unused argument(s) compilation warning */
434 UNUSED(hspi);
436 /* NOTE : This function should not be modified, when the callback is needed,
437 the HAL_SPI_MspInit should be implemented in the user file
442 * @brief De-Initialize the SPI MSP.
443 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
444 * the configuration information for SPI module.
445 * @retval None
447 __weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi)
449 /* Prevent unused argument(s) compilation warning */
450 UNUSED(hspi);
452 /* NOTE : This function should not be modified, when the callback is needed,
453 the HAL_SPI_MspDeInit should be implemented in the user file
458 * @}
461 /** @defgroup SPI_Exported_Functions_Group2 IO operation functions
462 * @brief Data transfers functions
464 @verbatim
465 ==============================================================================
466 ##### IO operation functions #####
467 ===============================================================================
468 [..]
469 This subsection provides a set of functions allowing to manage the SPI
470 data transfers.
472 [..] The SPI supports master and slave mode :
474 (#) There are two modes of transfer:
475 (++) Blocking mode: The communication is performed in polling mode.
476 The HAL status of all data processing is returned by the same function
477 after finishing transfer.
478 (++) No-Blocking mode: The communication is performed using Interrupts
479 or DMA, These APIs return the HAL status.
480 The end of the data processing will be indicated through the
481 dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when
482 using DMA mode.
483 The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks
484 will be executed respectively at the end of the transmit or Receive process
485 The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected
487 (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA)
488 exist for 1Line (simplex) and 2Lines (full duplex) modes.
490 @endverbatim
491 * @{
495 * @brief Transmit an amount of data in blocking mode.
496 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
497 * the configuration information for SPI module.
498 * @param pData pointer to data buffer
499 * @param Size amount of data to be sent
500 * @param Timeout Timeout duration
501 * @retval HAL status
503 HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
505 uint32_t tickstart = 0U;
506 HAL_StatusTypeDef errorcode = HAL_OK;
509 /* Check Direction parameter */
510 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
512 /* Process Locked */
513 __HAL_LOCK(hspi);
515 /* Init tickstart for timeout management*/
516 tickstart = HAL_GetTick();
518 if (hspi->State != HAL_SPI_STATE_READY)
520 errorcode = HAL_BUSY;
521 goto error;
524 if ((pData == NULL) || (Size == 0U))
526 errorcode = HAL_ERROR;
527 goto error;
530 /* Set the transaction information */
531 hspi->State = HAL_SPI_STATE_BUSY_TX;
532 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
533 hspi->pTxBuffPtr = (uint8_t *)pData;
534 hspi->TxXferSize = Size;
535 hspi->TxXferCount = Size;
537 /*Init field not used in handle to zero */
538 hspi->pRxBuffPtr = (uint8_t *)NULL;
539 hspi->RxXferSize = 0U;
540 hspi->RxXferCount = 0U;
541 hspi->TxISR = NULL;
542 hspi->RxISR = NULL;
544 /* Configure communication direction : 1Line */
545 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
547 SPI_1LINE_TX(hspi);
550 #if (USE_SPI_CRC != 0U)
551 /* Reset CRC Calculation */
552 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
554 SPI_RESET_CRC(hspi);
556 #endif /* USE_SPI_CRC */
558 /* Check if the SPI is already enabled */
559 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
561 /* Enable SPI peripheral */
562 __HAL_SPI_ENABLE(hspi);
565 /* Transmit data in 16 Bit mode */
566 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
568 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
570 hspi->Instance->DR = *((uint16_t *)pData);
571 pData += sizeof(uint16_t);
572 hspi->TxXferCount--;
574 /* Transmit data in 16 Bit mode */
575 while (hspi->TxXferCount > 0U)
577 /* Wait until TXE flag is set to send data */
578 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
580 hspi->Instance->DR = *((uint16_t *)pData);
581 pData += sizeof(uint16_t);
582 hspi->TxXferCount--;
584 else
586 /* Timeout management */
587 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
589 errorcode = HAL_TIMEOUT;
590 goto error;
595 /* Transmit data in 8 Bit mode */
596 else
598 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
600 if (hspi->TxXferCount > 1U)
602 /* write on the data register in packing mode */
603 hspi->Instance->DR = *((uint16_t *)pData);
604 pData += sizeof(uint16_t);
605 hspi->TxXferCount -= 2U;
607 else
609 *((__IO uint8_t *)&hspi->Instance->DR) = (*pData++);
610 hspi->TxXferCount--;
613 while (hspi->TxXferCount > 0U)
615 /* Wait until TXE flag is set to send data */
616 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
618 if (hspi->TxXferCount > 1U)
620 /* write on the data register in packing mode */
621 hspi->Instance->DR = *((uint16_t *)pData);
622 pData += sizeof(uint16_t);
623 hspi->TxXferCount -= 2U;
625 else
627 *((__IO uint8_t *)&hspi->Instance->DR) = (*pData++);
628 hspi->TxXferCount--;
631 else
633 /* Timeout management */
634 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
636 errorcode = HAL_TIMEOUT;
637 goto error;
642 #if (USE_SPI_CRC != 0U)
643 /* Enable CRC Transmission */
644 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
646 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
648 #endif /* USE_SPI_CRC */
650 /* Check the end of the transaction */
651 if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
653 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
656 /* Clear overrun flag in 2 Lines communication mode because received is not read */
657 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
659 __HAL_SPI_CLEAR_OVRFLAG(hspi);
662 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
664 errorcode = HAL_ERROR;
667 error:
668 hspi->State = HAL_SPI_STATE_READY;
669 /* Process Unlocked */
670 __HAL_UNLOCK(hspi);
671 return errorcode;
675 * @brief Receive an amount of data in blocking mode.
676 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
677 * the configuration information for SPI module.
678 * @param pData pointer to data buffer
679 * @param Size amount of data to be received
680 * @param Timeout Timeout duration
681 * @retval HAL status
683 HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
685 #if (USE_SPI_CRC != 0U)
686 __IO uint16_t tmpreg = 0U;
687 #endif /* USE_SPI_CRC */
688 uint32_t tickstart = 0U;
689 HAL_StatusTypeDef errorcode = HAL_OK;
692 if ((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES))
694 hspi->State = HAL_SPI_STATE_BUSY_RX;
695 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
696 return HAL_SPI_TransmitReceive(hspi, pData, pData, Size, Timeout);
699 /* Process Locked */
700 __HAL_LOCK(hspi);
702 /* Init tickstart for timeout management*/
703 tickstart = HAL_GetTick();
705 if (hspi->State != HAL_SPI_STATE_READY)
707 errorcode = HAL_BUSY;
708 goto error;
711 if ((pData == NULL) || (Size == 0U))
713 errorcode = HAL_ERROR;
714 goto error;
717 /* Set the transaction information */
718 hspi->State = HAL_SPI_STATE_BUSY_RX;
719 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
720 hspi->pRxBuffPtr = (uint8_t *)pData;
721 hspi->RxXferSize = Size;
722 hspi->RxXferCount = Size;
724 /*Init field not used in handle to zero */
725 hspi->pTxBuffPtr = (uint8_t *)NULL;
726 hspi->TxXferSize = 0U;
727 hspi->TxXferCount = 0U;
728 hspi->RxISR = NULL;
729 hspi->TxISR = NULL;
731 #if (USE_SPI_CRC != 0U)
732 /* Reset CRC Calculation */
733 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
735 SPI_RESET_CRC(hspi);
736 /* this is done to handle the CRCNEXT before the latest data */
737 hspi->RxXferCount--;
739 #endif /* USE_SPI_CRC */
741 /* Set the Rx FiFo threshold */
742 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
744 /* set fiforxthresold according the reception data length: 16bit */
745 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
747 else
749 /* set fiforxthresold according the reception data length: 8bit */
750 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
753 /* Configure communication direction: 1Line */
754 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
756 SPI_1LINE_RX(hspi);
759 /* Check if the SPI is already enabled */
760 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
762 /* Enable SPI peripheral */
763 __HAL_SPI_ENABLE(hspi);
766 /* Receive data in 8 Bit mode */
767 if (hspi->Init.DataSize <= SPI_DATASIZE_8BIT)
769 /* Transfer loop */
770 while (hspi->RxXferCount > 0U)
772 /* Check the RXNE flag */
773 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
775 /* read the received data */
776 (* (uint8_t *)pData) = *(__IO uint8_t *)&hspi->Instance->DR;
777 pData += sizeof(uint8_t);
778 hspi->RxXferCount--;
780 else
782 /* Timeout management */
783 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
785 errorcode = HAL_TIMEOUT;
786 goto error;
791 else
793 /* Transfer loop */
794 while (hspi->RxXferCount > 0U)
796 /* Check the RXNE flag */
797 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
799 *((uint16_t *)pData) = hspi->Instance->DR;
800 pData += sizeof(uint16_t);
801 hspi->RxXferCount--;
803 else
805 /* Timeout management */
806 if ((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout)))
808 errorcode = HAL_TIMEOUT;
809 goto error;
815 #if (USE_SPI_CRC != 0U)
816 /* Handle the CRC Transmission */
817 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
819 /* freeze the CRC before the latest data */
820 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
822 /* Read the latest data */
823 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
825 /* the latest data has not been received */
826 errorcode = HAL_TIMEOUT;
827 goto error;
830 /* Receive last data in 16 Bit mode */
831 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
833 *((uint16_t *)pData) = hspi->Instance->DR;
835 /* Receive last data in 8 Bit mode */
836 else
838 (*(uint8_t *)pData) = *(__IO uint8_t *)&hspi->Instance->DR;
841 /* Wait the CRC data */
842 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
844 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
845 errorcode = HAL_TIMEOUT;
846 goto error;
849 /* Read CRC to Flush DR and RXNE flag */
850 if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
852 tmpreg = hspi->Instance->DR;
853 /* To avoid GCC warning */
854 UNUSED(tmpreg);
856 else
858 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
859 /* To avoid GCC warning */
860 UNUSED(tmpreg);
862 if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
864 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, Timeout, tickstart) != HAL_OK)
866 /* Error on the CRC reception */
867 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
868 errorcode = HAL_TIMEOUT;
869 goto error;
871 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
872 /* To avoid GCC warning */
873 UNUSED(tmpreg);
877 #endif /* USE_SPI_CRC */
879 /* Check the end of the transaction */
880 if (SPI_EndRxTransaction(hspi, Timeout, tickstart) != HAL_OK)
882 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
885 #if (USE_SPI_CRC != 0U)
886 /* Check if CRC error occurred */
887 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
889 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
890 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
892 #endif /* USE_SPI_CRC */
894 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
896 errorcode = HAL_ERROR;
899 error :
900 hspi->State = HAL_SPI_STATE_READY;
901 __HAL_UNLOCK(hspi);
902 return errorcode;
906 * @brief Transmit and Receive an amount of data in blocking mode.
907 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
908 * the configuration information for SPI module.
909 * @param pTxData pointer to transmission data buffer
910 * @param pRxData pointer to reception data buffer
911 * @param Size amount of data to be sent and received
912 * @param Timeout Timeout duration
913 * @retval HAL status
915 HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size,
916 uint32_t Timeout)
918 uint32_t tmp = 0U, tmp1 = 0U;
919 #if (USE_SPI_CRC != 0U)
920 __IO uint16_t tmpreg = 0U;
921 #endif /* USE_SPI_CRC */
922 uint32_t tickstart = 0U;
923 /* Variable used to alternate Rx and Tx during transfer */
924 uint32_t txallowed = 1U;
925 HAL_StatusTypeDef errorcode = HAL_OK;
928 /* Check Direction parameter */
929 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
931 /* Process Locked */
932 __HAL_LOCK(hspi);
934 /* Init tickstart for timeout management*/
935 tickstart = HAL_GetTick();
937 tmp = hspi->State;
938 tmp1 = hspi->Init.Mode;
940 if (!((tmp == HAL_SPI_STATE_READY) || \
941 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
943 errorcode = HAL_BUSY;
944 goto error;
947 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
949 errorcode = HAL_ERROR;
950 goto error;
953 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
954 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
956 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
959 /* Set the transaction information */
960 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
961 hspi->pRxBuffPtr = (uint8_t *)pRxData;
962 hspi->RxXferCount = Size;
963 hspi->RxXferSize = Size;
964 hspi->pTxBuffPtr = (uint8_t *)pTxData;
965 hspi->TxXferCount = Size;
966 hspi->TxXferSize = Size;
968 /*Init field not used in handle to zero */
969 hspi->RxISR = NULL;
970 hspi->TxISR = NULL;
972 #if (USE_SPI_CRC != 0U)
973 /* Reset CRC Calculation */
974 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
976 SPI_RESET_CRC(hspi);
978 #endif /* USE_SPI_CRC */
980 /* Set the Rx Fifo threshold */
981 if ((hspi->Init.DataSize > SPI_DATASIZE_8BIT) || (hspi->RxXferCount > 1U))
983 /* set fiforxthreshold according the reception data length: 16bit */
984 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
986 else
988 /* set fiforxthreshold according the reception data length: 8bit */
989 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
992 /* Check if the SPI is already enabled */
993 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
995 /* Enable SPI peripheral */
996 __HAL_SPI_ENABLE(hspi);
999 /* Transmit and Receive data in 16 Bit mode */
1000 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1002 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
1004 hspi->Instance->DR = *((uint16_t *)pTxData);
1005 pTxData += sizeof(uint16_t);
1006 hspi->TxXferCount--;
1008 while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
1010 /* Check TXE flag */
1011 if (txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
1013 hspi->Instance->DR = *((uint16_t *)pTxData);
1014 pTxData += sizeof(uint16_t);
1015 hspi->TxXferCount--;
1016 /* Next Data is a reception (Rx). Tx not allowed */
1017 txallowed = 0U;
1019 #if (USE_SPI_CRC != 0U)
1020 /* Enable CRC Transmission */
1021 if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
1023 /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
1024 if (((hspi->Instance->CR1 & SPI_CR1_MSTR) == 0U) && ((hspi->Instance->CR2 & SPI_CR2_NSSP) == SPI_CR2_NSSP))
1026 SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
1028 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
1030 #endif /* USE_SPI_CRC */
1033 /* Check RXNE flag */
1034 if ((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
1036 *((uint16_t *)pRxData) = hspi->Instance->DR;
1037 pRxData += sizeof(uint16_t);
1038 hspi->RxXferCount--;
1039 /* Next Data is a Transmission (Tx). Tx is allowed */
1040 txallowed = 1U;
1042 if ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout))
1044 errorcode = HAL_TIMEOUT;
1045 goto error;
1049 /* Transmit and Receive data in 8 Bit mode */
1050 else
1052 if ((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
1054 if (hspi->TxXferCount > 1U)
1056 hspi->Instance->DR = *((uint16_t *)pTxData);
1057 pTxData += sizeof(uint16_t);
1058 hspi->TxXferCount -= 2U;
1060 else
1062 *(__IO uint8_t *)&hspi->Instance->DR = (*pTxData++);
1063 hspi->TxXferCount--;
1066 while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
1068 /* check TXE flag */
1069 if (txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
1071 if (hspi->TxXferCount > 1U)
1073 hspi->Instance->DR = *((uint16_t *)pTxData);
1074 pTxData += sizeof(uint16_t);
1075 hspi->TxXferCount -= 2U;
1077 else
1079 *(__IO uint8_t *)&hspi->Instance->DR = (*pTxData++);
1080 hspi->TxXferCount--;
1082 /* Next Data is a reception (Rx). Tx not allowed */
1083 txallowed = 0U;
1085 #if (USE_SPI_CRC != 0U)
1086 /* Enable CRC Transmission */
1087 if ((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
1089 /* Set NSS Soft to received correctly the CRC on slave mode with NSS pulse activated */
1090 if (((hspi->Instance->CR1 & SPI_CR1_MSTR) == 0U) && ((hspi->Instance->CR2 & SPI_CR2_NSSP) == SPI_CR2_NSSP))
1092 SET_BIT(hspi->Instance->CR1, SPI_CR1_SSM);
1094 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
1096 #endif /* USE_SPI_CRC */
1099 /* Wait until RXNE flag is reset */
1100 if ((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
1102 if (hspi->RxXferCount > 1U)
1104 *((uint16_t *)pRxData) = hspi->Instance->DR;
1105 pRxData += sizeof(uint16_t);
1106 hspi->RxXferCount -= 2U;
1107 if (hspi->RxXferCount <= 1U)
1109 /* set fiforxthresold before to switch on 8 bit data size */
1110 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1113 else
1115 (*(uint8_t *)pRxData++) = *(__IO uint8_t *)&hspi->Instance->DR;
1116 hspi->RxXferCount--;
1118 /* Next Data is a Transmission (Tx). Tx is allowed */
1119 txallowed = 1U;
1121 if ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick() - tickstart) >= Timeout))
1123 errorcode = HAL_TIMEOUT;
1124 goto error;
1129 #if (USE_SPI_CRC != 0U)
1130 /* Read CRC from DR to close CRC calculation process */
1131 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1133 /* Wait until TXE flag */
1134 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
1136 /* Error on the CRC reception */
1137 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1138 errorcode = HAL_TIMEOUT;
1139 goto error;
1141 /* Read CRC */
1142 if (hspi->Init.DataSize == SPI_DATASIZE_16BIT)
1144 tmpreg = hspi->Instance->DR;
1145 /* To avoid GCC warning */
1146 UNUSED(tmpreg);
1148 else
1150 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
1151 /* To avoid GCC warning */
1152 UNUSED(tmpreg);
1154 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
1156 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
1158 /* Error on the CRC reception */
1159 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1160 errorcode = HAL_TIMEOUT;
1161 goto error;
1163 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
1164 /* To avoid GCC warning */
1165 UNUSED(tmpreg);
1170 /* Check if CRC error occurred */
1171 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
1173 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
1174 /* Clear CRC Flag */
1175 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
1177 errorcode = HAL_ERROR;
1179 #endif /* USE_SPI_CRC */
1181 /* Check the end of the transaction */
1182 if (SPI_EndRxTxTransaction(hspi, Timeout, tickstart) != HAL_OK)
1184 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
1187 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
1189 errorcode = HAL_ERROR;
1192 error :
1193 hspi->State = HAL_SPI_STATE_READY;
1194 __HAL_UNLOCK(hspi);
1195 return errorcode;
1199 * @brief Transmit an amount of data in non-blocking mode with Interrupt.
1200 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1201 * the configuration information for SPI module.
1202 * @param pData pointer to data buffer
1203 * @param Size amount of data to be sent
1204 * @retval HAL status
1206 HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1208 HAL_StatusTypeDef errorcode = HAL_OK;
1211 /* Check Direction parameter */
1212 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1214 /* Process Locked */
1215 __HAL_LOCK(hspi);
1217 if ((pData == NULL) || (Size == 0U))
1219 errorcode = HAL_ERROR;
1220 goto error;
1223 if (hspi->State != HAL_SPI_STATE_READY)
1225 errorcode = HAL_BUSY;
1226 goto error;
1229 /* Set the transaction information */
1230 hspi->State = HAL_SPI_STATE_BUSY_TX;
1231 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1232 hspi->pTxBuffPtr = (uint8_t *)pData;
1233 hspi->TxXferSize = Size;
1234 hspi->TxXferCount = Size;
1236 /* Init field not used in handle to zero */
1237 hspi->pRxBuffPtr = (uint8_t *)NULL;
1238 hspi->RxXferSize = 0U;
1239 hspi->RxXferCount = 0U;
1240 hspi->RxISR = NULL;
1242 /* Set the function for IT treatment */
1243 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1245 hspi->TxISR = SPI_TxISR_16BIT;
1247 else
1249 hspi->TxISR = SPI_TxISR_8BIT;
1252 /* Configure communication direction : 1Line */
1253 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1255 SPI_1LINE_TX(hspi);
1258 #if (USE_SPI_CRC != 0U)
1259 /* Reset CRC Calculation */
1260 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1262 SPI_RESET_CRC(hspi);
1264 #endif /* USE_SPI_CRC */
1266 /* Enable TXE and ERR interrupt */
1267 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
1270 /* Check if the SPI is already enabled */
1271 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1273 /* Enable SPI peripheral */
1274 __HAL_SPI_ENABLE(hspi);
1277 error :
1278 __HAL_UNLOCK(hspi);
1279 return errorcode;
1283 * @brief Receive an amount of data in non-blocking mode with Interrupt.
1284 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1285 * the configuration information for SPI module.
1286 * @param pData pointer to data buffer
1287 * @param Size amount of data to be sent
1288 * @retval HAL status
1290 HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1292 HAL_StatusTypeDef errorcode = HAL_OK;
1295 if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
1297 hspi->State = HAL_SPI_STATE_BUSY_RX;
1298 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1299 return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size);
1302 /* Process Locked */
1303 __HAL_LOCK(hspi);
1305 if (hspi->State != HAL_SPI_STATE_READY)
1307 errorcode = HAL_BUSY;
1308 goto error;
1311 if ((pData == NULL) || (Size == 0U))
1313 errorcode = HAL_ERROR;
1314 goto error;
1317 /* Set the transaction information */
1318 hspi->State = HAL_SPI_STATE_BUSY_RX;
1319 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1320 hspi->pRxBuffPtr = (uint8_t *)pData;
1321 hspi->RxXferSize = Size;
1322 hspi->RxXferCount = Size;
1324 /* Init field not used in handle to zero */
1325 hspi->pTxBuffPtr = (uint8_t *)NULL;
1326 hspi->TxXferSize = 0U;
1327 hspi->TxXferCount = 0U;
1328 hspi->TxISR = NULL;
1330 /* Check the data size to adapt Rx threshold and the set the function for IT treatment */
1331 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1333 /* Set fiforxthresold according the reception data length: 16 bit */
1334 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1335 hspi->RxISR = SPI_RxISR_16BIT;
1337 else
1339 /* Set fiforxthresold according the reception data length: 8 bit */
1340 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1341 hspi->RxISR = SPI_RxISR_8BIT;
1344 /* Configure communication direction : 1Line */
1345 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1347 SPI_1LINE_RX(hspi);
1350 #if (USE_SPI_CRC != 0U)
1351 /* Reset CRC Calculation */
1352 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1354 hspi->CRCSize = 1U;
1355 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
1357 hspi->CRCSize = 2U;
1359 SPI_RESET_CRC(hspi);
1361 else
1363 hspi->CRCSize = 0U;
1365 #endif /* USE_SPI_CRC */
1367 /* Enable TXE and ERR interrupt */
1368 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
1370 /* Note : The SPI must be enabled after unlocking current process
1371 to avoid the risk of SPI interrupt handle execution before current
1372 process unlock */
1374 /* Check if the SPI is already enabled */
1375 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1377 /* Enable SPI peripheral */
1378 __HAL_SPI_ENABLE(hspi);
1381 error :
1382 /* Process Unlocked */
1383 __HAL_UNLOCK(hspi);
1384 return errorcode;
1388 * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt.
1389 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1390 * the configuration information for SPI module.
1391 * @param pTxData pointer to transmission data buffer
1392 * @param pRxData pointer to reception data buffer
1393 * @param Size amount of data to be sent and received
1394 * @retval HAL status
1396 HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
1398 uint32_t tmp = 0U, tmp1 = 0U;
1399 HAL_StatusTypeDef errorcode = HAL_OK;
1402 /* Check Direction parameter */
1403 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1405 /* Process locked */
1406 __HAL_LOCK(hspi);
1408 tmp = hspi->State;
1409 tmp1 = hspi->Init.Mode;
1411 if (!((tmp == HAL_SPI_STATE_READY) || \
1412 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1414 errorcode = HAL_BUSY;
1415 goto error;
1418 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
1420 errorcode = HAL_ERROR;
1421 goto error;
1424 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1425 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
1427 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1430 /* Set the transaction information */
1431 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1432 hspi->pTxBuffPtr = (uint8_t *)pTxData;
1433 hspi->TxXferSize = Size;
1434 hspi->TxXferCount = Size;
1435 hspi->pRxBuffPtr = (uint8_t *)pRxData;
1436 hspi->RxXferSize = Size;
1437 hspi->RxXferCount = Size;
1439 /* Set the function for IT treatment */
1440 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1442 hspi->RxISR = SPI_2linesRxISR_16BIT;
1443 hspi->TxISR = SPI_2linesTxISR_16BIT;
1445 else
1447 hspi->RxISR = SPI_2linesRxISR_8BIT;
1448 hspi->TxISR = SPI_2linesTxISR_8BIT;
1451 #if (USE_SPI_CRC != 0U)
1452 /* Reset CRC Calculation */
1453 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1455 hspi->CRCSize = 1U;
1456 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT))
1458 hspi->CRCSize = 2U;
1460 SPI_RESET_CRC(hspi);
1462 else
1464 hspi->CRCSize = 0U;
1466 #endif /* USE_SPI_CRC */
1468 /* Check if packing mode is enabled and if there is more than 2 data to receive */
1469 if ((hspi->Init.DataSize > SPI_DATASIZE_8BIT) || (hspi->RxXferCount >= 2U))
1471 /* Set fiforxthresold according the reception data length: 16 bit */
1472 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1474 else
1476 /* Set fiforxthresold according the reception data length: 8 bit */
1477 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1480 /* Enable TXE, RXNE and ERR interrupt */
1481 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
1483 /* Check if the SPI is already enabled */
1484 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1486 /* Enable SPI peripheral */
1487 __HAL_SPI_ENABLE(hspi);
1490 error :
1491 /* Process Unlocked */
1492 __HAL_UNLOCK(hspi);
1493 return errorcode;
1497 * @brief Transmit an amount of data in non-blocking mode with DMA.
1498 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1499 * the configuration information for SPI module.
1500 * @param pData pointer to data buffer
1501 * @param Size amount of data to be sent
1502 * @retval HAL status
1504 HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1506 HAL_StatusTypeDef errorcode = HAL_OK;
1508 /* check tx dma handle */
1509 assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
1511 /* Check Direction parameter */
1512 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1514 /* Process Locked */
1515 __HAL_LOCK(hspi);
1517 if (hspi->State != HAL_SPI_STATE_READY)
1519 errorcode = HAL_BUSY;
1520 goto error;
1523 if ((pData == NULL) || (Size == 0U))
1525 errorcode = HAL_ERROR;
1526 goto error;
1529 /* Set the transaction information */
1530 hspi->State = HAL_SPI_STATE_BUSY_TX;
1531 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1532 hspi->pTxBuffPtr = (uint8_t *)pData;
1533 hspi->TxXferSize = Size;
1534 hspi->TxXferCount = Size;
1536 /* Init field not used in handle to zero */
1537 hspi->pRxBuffPtr = (uint8_t *)NULL;
1538 hspi->TxISR = NULL;
1539 hspi->RxISR = NULL;
1540 hspi->RxXferSize = 0U;
1541 hspi->RxXferCount = 0U;
1543 /* Configure communication direction : 1Line */
1544 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1546 SPI_1LINE_TX(hspi);
1549 #if (USE_SPI_CRC != 0U)
1550 /* Reset CRC Calculation */
1551 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1553 SPI_RESET_CRC(hspi);
1555 #endif /* USE_SPI_CRC */
1557 /* Set the SPI TxDMA Half transfer complete callback */
1558 hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt;
1560 /* Set the SPI TxDMA transfer complete callback */
1561 hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt;
1563 /* Set the DMA error callback */
1564 hspi->hdmatx->XferErrorCallback = SPI_DMAError;
1566 /* Set the DMA AbortCpltCallback */
1567 hspi->hdmatx->XferAbortCallback = NULL;
1569 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1570 /* Packing mode is enabled only if the DMA setting is HALWORD */
1571 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
1573 /* Check the even/odd of the data size + crc if enabled */
1574 if ((hspi->TxXferCount & 0x1U) == 0U)
1576 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1577 hspi->TxXferCount = (hspi->TxXferCount >> 1U);
1579 else
1581 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1582 hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
1586 /* Enable the Tx DMA Stream/Channel */
1587 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1589 /* Check if the SPI is already enabled */
1590 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1592 /* Enable SPI peripheral */
1593 __HAL_SPI_ENABLE(hspi);
1596 /* Enable the SPI Error Interrupt Bit */
1597 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1599 /* Enable Tx DMA Request */
1600 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1602 error :
1603 /* Process Unlocked */
1604 __HAL_UNLOCK(hspi);
1605 return errorcode;
1609 * @brief Receive an amount of data in non-blocking mode with DMA.
1610 * @note In case of MASTER mode and SPI_DIRECTION_2LINES direction, hdmatx shall be defined.
1611 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1612 * the configuration information for SPI module.
1613 * @param pData pointer to data buffer
1614 * @note When the CRC feature is enabled the pData Length must be Size + 1.
1615 * @param Size amount of data to be sent
1616 * @retval HAL status
1618 HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1620 HAL_StatusTypeDef errorcode = HAL_OK;
1622 /* check rx dma handle */
1623 assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx));
1625 if ((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
1627 hspi->State = HAL_SPI_STATE_BUSY_RX;
1629 /* check tx dma handle */
1630 assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
1632 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1633 return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size);
1636 /* Process Locked */
1637 __HAL_LOCK(hspi);
1639 if (hspi->State != HAL_SPI_STATE_READY)
1641 errorcode = HAL_BUSY;
1642 goto error;
1645 if ((pData == NULL) || (Size == 0U))
1647 errorcode = HAL_ERROR;
1648 goto error;
1651 /* Set the transaction information */
1652 hspi->State = HAL_SPI_STATE_BUSY_RX;
1653 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1654 hspi->pRxBuffPtr = (uint8_t *)pData;
1655 hspi->RxXferSize = Size;
1656 hspi->RxXferCount = Size;
1658 /*Init field not used in handle to zero */
1659 hspi->RxISR = NULL;
1660 hspi->TxISR = NULL;
1661 hspi->TxXferSize = 0U;
1662 hspi->TxXferCount = 0U;
1664 /* Configure communication direction : 1Line */
1665 if (hspi->Init.Direction == SPI_DIRECTION_1LINE)
1667 SPI_1LINE_RX(hspi);
1670 #if (USE_SPI_CRC != 0U)
1671 /* Reset CRC Calculation */
1672 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1674 SPI_RESET_CRC(hspi);
1676 #endif /* USE_SPI_CRC */
1678 #if defined (STM32F302xC) || defined (STM32F303xC) || defined (STM32F373xC) || defined (STM32F358xx) || defined (STM32F378xx)
1679 /* Packing mode management is enabled by the DMA settings */
1680 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
1682 /* Restriction the DMA data received is not allowed in this mode */
1683 errorcode = HAL_ERROR;
1684 goto error;
1686 #endif
1688 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1689 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1691 /* Set fiforxthresold according the reception data length: 16bit */
1692 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1694 else
1696 /* Set fiforxthresold according the reception data length: 8bit */
1697 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1699 if (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1701 /* set fiforxthresold according the reception data length: 16bit */
1702 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1704 if ((hspi->RxXferCount & 0x1U) == 0x0U)
1706 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1707 hspi->RxXferCount = hspi->RxXferCount >> 1U;
1709 else
1711 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1712 hspi->RxXferCount = (hspi->RxXferCount >> 1U) + 1U;
1717 /* Set the SPI RxDMA Half transfer complete callback */
1718 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1720 /* Set the SPI Rx DMA transfer complete callback */
1721 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1723 /* Set the DMA error callback */
1724 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1726 /* Set the DMA AbortCpltCallback */
1727 hspi->hdmarx->XferAbortCallback = NULL;
1729 /* Enable the Rx DMA Stream/Channel */
1730 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1732 /* Check if the SPI is already enabled */
1733 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1735 /* Enable SPI peripheral */
1736 __HAL_SPI_ENABLE(hspi);
1739 /* Enable the SPI Error Interrupt Bit */
1740 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1742 /* Enable Rx DMA Request */
1743 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1745 error:
1746 /* Process Unlocked */
1747 __HAL_UNLOCK(hspi);
1748 return errorcode;
1752 * @brief Transmit and Receive an amount of data in non-blocking mode with DMA.
1753 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
1754 * the configuration information for SPI module.
1755 * @param pTxData pointer to transmission data buffer
1756 * @param pRxData pointer to reception data buffer
1757 * @note When the CRC feature is enabled the pRxData Length must be Size + 1
1758 * @param Size amount of data to be sent
1759 * @retval HAL status
1761 HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData,
1762 uint16_t Size)
1764 uint32_t tmp = 0U, tmp1 = 0U;
1765 HAL_StatusTypeDef errorcode = HAL_OK;
1767 /* check rx & tx dma handles */
1768 assert_param(IS_SPI_DMA_HANDLE(hspi->hdmarx));
1769 assert_param(IS_SPI_DMA_HANDLE(hspi->hdmatx));
1771 /* Check Direction parameter */
1772 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1774 /* Process locked */
1775 __HAL_LOCK(hspi);
1777 tmp = hspi->State;
1778 tmp1 = hspi->Init.Mode;
1779 if (!((tmp == HAL_SPI_STATE_READY) ||
1780 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1782 errorcode = HAL_BUSY;
1783 goto error;
1786 if ((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
1788 errorcode = HAL_ERROR;
1789 goto error;
1792 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1793 if (hspi->State != HAL_SPI_STATE_BUSY_RX)
1795 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1798 /* Set the transaction information */
1799 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1800 hspi->pTxBuffPtr = (uint8_t *)pTxData;
1801 hspi->TxXferSize = Size;
1802 hspi->TxXferCount = Size;
1803 hspi->pRxBuffPtr = (uint8_t *)pRxData;
1804 hspi->RxXferSize = Size;
1805 hspi->RxXferCount = Size;
1807 /* Init field not used in handle to zero */
1808 hspi->RxISR = NULL;
1809 hspi->TxISR = NULL;
1811 #if (USE_SPI_CRC != 0U)
1812 /* Reset CRC Calculation */
1813 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1815 SPI_RESET_CRC(hspi);
1817 #endif /* USE_SPI_CRC */
1820 #if defined (STM32F302xC) || defined (STM32F303xC) || defined (STM32F373xC) || defined (STM32F358xx) || defined (STM32F378xx)
1821 /* packing mode management is enabled by the DMA settings */
1822 if ((hspi->Init.DataSize <= SPI_DATASIZE_8BIT) && (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD))
1824 /* Restriction the DMA data received is not allowed in this mode */
1825 errorcode = HAL_ERROR;
1826 goto error;
1828 #endif
1830 /* Reset the threshold bit */
1831 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX | SPI_CR2_LDMARX);
1833 /* The packing mode management is enabled by the DMA settings according the spi data size */
1834 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
1836 /* Set fiforxthreshold according the reception data length: 16bit */
1837 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1839 else
1841 /* Set fiforxthresold according the reception data length: 8bit */
1842 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1844 if (hspi->hdmatx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1846 if ((hspi->TxXferSize & 0x1U) == 0x0U)
1848 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1849 hspi->TxXferCount = hspi->TxXferCount >> 1U;
1851 else
1853 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMATX);
1854 hspi->TxXferCount = (hspi->TxXferCount >> 1U) + 1U;
1858 if (hspi->hdmarx->Init.MemDataAlignment == DMA_MDATAALIGN_HALFWORD)
1860 /* Set fiforxthresold according the reception data length: 16bit */
1861 CLEAR_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
1863 if ((hspi->RxXferCount & 0x1U) == 0x0U)
1865 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1866 hspi->RxXferCount = hspi->RxXferCount >> 1U;
1868 else
1870 SET_BIT(hspi->Instance->CR2, SPI_CR2_LDMARX);
1871 hspi->RxXferCount = (hspi->RxXferCount >> 1U) + 1U;
1876 /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */
1877 if (hspi->State == HAL_SPI_STATE_BUSY_RX)
1879 /* Set the SPI Rx DMA Half transfer complete callback */
1880 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1881 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1883 else
1885 /* Set the SPI Tx/Rx DMA Half transfer complete callback */
1886 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt;
1887 hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt;
1890 /* Set the DMA error callback */
1891 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1893 /* Set the DMA AbortCpltCallback */
1894 hspi->hdmarx->XferAbortCallback = NULL;
1896 /* Enable the Rx DMA Stream/Channel */
1897 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1899 /* Enable Rx DMA Request */
1900 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1902 /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing
1903 is performed in DMA reception complete callback */
1904 hspi->hdmatx->XferHalfCpltCallback = NULL;
1905 hspi->hdmatx->XferCpltCallback = NULL;
1906 hspi->hdmatx->XferErrorCallback = NULL;
1907 hspi->hdmatx->XferAbortCallback = NULL;
1909 /* Enable the Tx DMA Stream/Channel */
1910 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1912 /* Check if the SPI is already enabled */
1913 if ((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
1915 /* Enable SPI peripheral */
1916 __HAL_SPI_ENABLE(hspi);
1918 /* Enable the SPI Error Interrupt Bit */
1919 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_ERR));
1921 /* Enable Tx DMA Request */
1922 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1924 error :
1925 /* Process Unlocked */
1926 __HAL_UNLOCK(hspi);
1927 return errorcode;
1931 * @brief Abort ongoing transfer (blocking mode).
1932 * @param hspi SPI handle.
1933 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
1934 * started in Interrupt or DMA mode.
1935 * This procedure performs following operations :
1936 * - Disable SPI Interrupts (depending of transfer direction)
1937 * - Disable the DMA transfer in the peripheral register (if enabled)
1938 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1939 * - Set handle State to READY
1940 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1941 * @retval HAL status
1943 HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi)
1945 HAL_StatusTypeDef errorcode;
1946 __IO uint32_t count, resetcount;
1948 /* Initialized local variable */
1949 errorcode = HAL_OK;
1950 resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
1951 count = resetcount;
1953 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
1954 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
1956 hspi->TxISR = SPI_AbortTx_ISR;
1957 /* Wait HAL_SPI_STATE_ABORT state */
1960 if (count-- == 0U)
1962 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
1963 break;
1966 while (hspi->State != HAL_SPI_STATE_ABORT);
1967 /* Reset Timeout Counter */
1968 count = resetcount;
1971 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
1973 hspi->RxISR = SPI_AbortRx_ISR;
1974 /* Wait HAL_SPI_STATE_ABORT state */
1977 if (count-- == 0U)
1979 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
1980 break;
1983 while (hspi->State != HAL_SPI_STATE_ABORT);
1984 /* Reset Timeout Counter */
1985 count = resetcount;
1988 /* Clear ERRIE interrupts in case of DMA Mode */
1989 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1991 /* Disable the SPI DMA Tx or SPI DMA Rx request if enabled */
1992 if ((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
1994 /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */
1995 if (hspi->hdmatx != NULL)
1997 /* Set the SPI DMA Abort callback :
1998 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
1999 hspi->hdmatx->XferAbortCallback = NULL;
2001 /* Abort DMA Tx Handle linked to SPI Peripheral */
2002 if (HAL_DMA_Abort(hspi->hdmatx) != HAL_OK)
2004 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2007 /* Disable Tx DMA Request */
2008 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN));
2010 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2012 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2015 /* Disable SPI Peripheral */
2016 __HAL_SPI_DISABLE(hspi);
2018 /* Empty the FRLVL fifo */
2019 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2021 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2024 /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */
2025 if (hspi->hdmarx != NULL)
2027 /* Set the SPI DMA Abort callback :
2028 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
2029 hspi->hdmarx->XferAbortCallback = NULL;
2031 /* Abort DMA Rx Handle linked to SPI Peripheral */
2032 if (HAL_DMA_Abort(hspi->hdmarx) != HAL_OK)
2034 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2037 /* Disable peripheral */
2038 __HAL_SPI_DISABLE(hspi);
2040 /* Control the BSY flag */
2041 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2043 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2046 /* Empty the FRLVL fifo */
2047 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2049 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2052 /* Disable Rx DMA Request */
2053 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN));
2056 /* Reset Tx and Rx transfer counters */
2057 hspi->RxXferCount = 0U;
2058 hspi->TxXferCount = 0U;
2060 /* Check error during Abort procedure */
2061 if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
2063 /* return HAL_Error in case of error during Abort procedure */
2064 errorcode = HAL_ERROR;
2066 else
2068 /* Reset errorCode */
2069 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2072 /* Clear the Error flags in the SR register */
2073 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2074 __HAL_SPI_CLEAR_FREFLAG(hspi);
2076 /* Restore hspi->state to ready */
2077 hspi->State = HAL_SPI_STATE_READY;
2079 return errorcode;
2083 * @brief Abort ongoing transfer (Interrupt mode).
2084 * @param hspi SPI handle.
2085 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
2086 * started in Interrupt or DMA mode.
2087 * This procedure performs following operations :
2088 * - Disable SPI Interrupts (depending of transfer direction)
2089 * - Disable the DMA transfer in the peripheral register (if enabled)
2090 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
2091 * - Set handle State to READY
2092 * - At abort completion, call user abort complete callback
2093 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
2094 * considered as completed only when user abort complete callback is executed (not when exiting function).
2095 * @retval HAL status
2097 HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi)
2099 HAL_StatusTypeDef errorcode;
2100 uint32_t abortcplt ;
2101 __IO uint32_t count, resetcount;
2103 /* Initialized local variable */
2104 errorcode = HAL_OK;
2105 abortcplt = 1U;
2106 resetcount = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
2107 count = resetcount;
2109 /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */
2110 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
2112 hspi->TxISR = SPI_AbortTx_ISR;
2113 /* Wait HAL_SPI_STATE_ABORT state */
2116 if (count-- == 0U)
2118 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
2119 break;
2122 while (hspi->State != HAL_SPI_STATE_ABORT);
2123 /* Reset Timeout Counter */
2124 count = resetcount;
2127 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
2129 hspi->RxISR = SPI_AbortRx_ISR;
2130 /* Wait HAL_SPI_STATE_ABORT state */
2133 if (count-- == 0U)
2135 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
2136 break;
2139 while (hspi->State != HAL_SPI_STATE_ABORT);
2140 /* Reset Timeout Counter */
2141 count = resetcount;
2144 /* Clear ERRIE interrupts in case of DMA Mode */
2145 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
2147 /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised
2148 before any call to DMA Abort functions */
2149 /* DMA Tx Handle is valid */
2150 if (hspi->hdmatx != NULL)
2152 /* Set DMA Abort Complete callback if UART DMA Tx request if enabled.
2153 Otherwise, set it to NULL */
2154 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
2156 hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback;
2158 else
2160 hspi->hdmatx->XferAbortCallback = NULL;
2163 /* DMA Rx Handle is valid */
2164 if (hspi->hdmarx != NULL)
2166 /* Set DMA Abort Complete callback if UART DMA Rx request if enabled.
2167 Otherwise, set it to NULL */
2168 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
2170 hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback;
2172 else
2174 hspi->hdmarx->XferAbortCallback = NULL;
2178 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2179 if ((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) && (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
2181 /* Abort the SPI DMA Tx Stream/Channel */
2182 if (hspi->hdmatx != NULL)
2184 /* Abort DMA Tx Handle linked to SPI Peripheral */
2185 if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
2187 hspi->hdmatx->XferAbortCallback = NULL;
2188 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2190 else
2192 abortcplt = 0U;
2195 /* Abort the SPI DMA Rx Stream/Channel */
2196 if (hspi->hdmarx != NULL)
2198 /* Abort DMA Rx Handle linked to SPI Peripheral */
2199 if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK)
2201 hspi->hdmarx->XferAbortCallback = NULL;
2202 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2203 abortcplt = 1U;
2205 else
2207 abortcplt = 0U;
2212 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2213 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
2215 /* Abort the SPI DMA Tx Stream/Channel */
2216 if (hspi->hdmatx != NULL)
2218 /* Abort DMA Tx Handle linked to SPI Peripheral */
2219 if (HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
2221 hspi->hdmatx->XferAbortCallback = NULL;
2222 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2224 else
2226 abortcplt = 0U;
2230 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
2231 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
2233 /* Abort the SPI DMA Rx Stream/Channel */
2234 if (hspi->hdmarx != NULL)
2236 /* Abort DMA Rx Handle linked to SPI Peripheral */
2237 if (HAL_DMA_Abort_IT(hspi->hdmarx) != HAL_OK)
2239 hspi->hdmarx->XferAbortCallback = NULL;
2240 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2242 else
2244 abortcplt = 0U;
2249 if (abortcplt == 1U)
2251 /* Reset Tx and Rx transfer counters */
2252 hspi->RxXferCount = 0U;
2253 hspi->TxXferCount = 0U;
2255 /* Check error during Abort procedure */
2256 if (hspi->ErrorCode == HAL_SPI_ERROR_ABORT)
2258 /* return HAL_Error in case of error during Abort procedure */
2259 errorcode = HAL_ERROR;
2261 else
2263 /* Reset errorCode */
2264 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2267 /* Clear the Error flags in the SR register */
2268 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2269 __HAL_SPI_CLEAR_FREFLAG(hspi);
2271 /* Restore hspi->State to Ready */
2272 hspi->State = HAL_SPI_STATE_READY;
2274 /* As no DMA to be aborted, call directly user Abort complete callback */
2275 HAL_SPI_AbortCpltCallback(hspi);
2278 return errorcode;
2282 * @brief Pause the DMA Transfer.
2283 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2284 * the configuration information for the specified SPI module.
2285 * @retval HAL status
2287 HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi)
2289 /* Process Locked */
2290 __HAL_LOCK(hspi);
2292 /* Disable the SPI DMA Tx & Rx requests */
2293 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2295 /* Process Unlocked */
2296 __HAL_UNLOCK(hspi);
2298 return HAL_OK;
2302 * @brief Resume the DMA Transfer.
2303 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2304 * the configuration information for the specified SPI module.
2305 * @retval HAL status
2307 HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi)
2309 /* Process Locked */
2310 __HAL_LOCK(hspi);
2312 /* Enable the SPI DMA Tx & Rx requests */
2313 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2315 /* Process Unlocked */
2316 __HAL_UNLOCK(hspi);
2318 return HAL_OK;
2322 * @brief Stop the DMA Transfer.
2323 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2324 * the configuration information for the specified SPI module.
2325 * @retval HAL status
2327 HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi)
2329 /* The Lock is not implemented on this API to allow the user application
2330 to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback():
2331 when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
2332 and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback()
2335 /* Abort the SPI DMA tx Stream/Channel */
2336 if (hspi->hdmatx != NULL)
2338 HAL_DMA_Abort(hspi->hdmatx);
2340 /* Abort the SPI DMA rx Stream/Channel */
2341 if (hspi->hdmarx != NULL)
2343 HAL_DMA_Abort(hspi->hdmarx);
2346 /* Disable the SPI DMA Tx & Rx requests */
2347 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2348 hspi->State = HAL_SPI_STATE_READY;
2349 return HAL_OK;
2353 * @brief Handle SPI interrupt request.
2354 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2355 * the configuration information for the specified SPI module.
2356 * @retval None
2358 void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi)
2360 uint32_t itsource = hspi->Instance->CR2;
2361 uint32_t itflag = hspi->Instance->SR;
2363 /* SPI in mode Receiver ----------------------------------------------------*/
2364 if (((itflag & SPI_FLAG_OVR) == RESET) &&
2365 ((itflag & SPI_FLAG_RXNE) != RESET) && ((itsource & SPI_IT_RXNE) != RESET))
2367 hspi->RxISR(hspi);
2368 return;
2371 /* SPI in mode Transmitter -------------------------------------------------*/
2372 if (((itflag & SPI_FLAG_TXE) != RESET) && ((itsource & SPI_IT_TXE) != RESET))
2374 hspi->TxISR(hspi);
2375 return;
2378 /* SPI in Error Treatment --------------------------------------------------*/
2379 if (((itflag & (SPI_FLAG_MODF | SPI_FLAG_OVR | SPI_FLAG_FRE)) != RESET) && ((itsource & SPI_IT_ERR) != RESET))
2381 /* SPI Overrun error interrupt occurred ----------------------------------*/
2382 if ((itflag & SPI_FLAG_OVR) != RESET)
2384 if (hspi->State != HAL_SPI_STATE_BUSY_TX)
2386 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR);
2387 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2389 else
2391 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2392 return;
2396 /* SPI Mode Fault error interrupt occurred -------------------------------*/
2397 if ((itflag & SPI_FLAG_MODF) != RESET)
2399 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF);
2400 __HAL_SPI_CLEAR_MODFFLAG(hspi);
2403 /* SPI Frame error interrupt occurred ------------------------------------*/
2404 if ((itflag & SPI_FLAG_FRE) != RESET)
2406 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE);
2407 __HAL_SPI_CLEAR_FREFLAG(hspi);
2410 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2412 /* Disable all interrupts */
2413 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR);
2415 hspi->State = HAL_SPI_STATE_READY;
2416 /* Disable the SPI DMA requests if enabled */
2417 if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN)))
2419 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN));
2421 /* Abort the SPI DMA Rx channel */
2422 if (hspi->hdmarx != NULL)
2424 /* Set the SPI DMA Abort callback :
2425 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2426 hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError;
2427 HAL_DMA_Abort_IT(hspi->hdmarx);
2429 /* Abort the SPI DMA Tx channel */
2430 if (hspi->hdmatx != NULL)
2432 /* Set the SPI DMA Abort callback :
2433 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2434 hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError;
2435 HAL_DMA_Abort_IT(hspi->hdmatx);
2438 else
2440 /* Call user error callback */
2441 HAL_SPI_ErrorCallback(hspi);
2444 return;
2449 * @brief Tx Transfer completed callback.
2450 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2451 * the configuration information for SPI module.
2452 * @retval None
2454 __weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi)
2456 /* Prevent unused argument(s) compilation warning */
2457 UNUSED(hspi);
2459 /* NOTE : This function should not be modified, when the callback is needed,
2460 the HAL_SPI_TxCpltCallback should be implemented in the user file
2465 * @brief Rx Transfer completed callback.
2466 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2467 * the configuration information for SPI module.
2468 * @retval None
2470 __weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi)
2472 /* Prevent unused argument(s) compilation warning */
2473 UNUSED(hspi);
2475 /* NOTE : This function should not be modified, when the callback is needed,
2476 the HAL_SPI_RxCpltCallback should be implemented in the user file
2481 * @brief Tx and Rx Transfer completed callback.
2482 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2483 * the configuration information for SPI module.
2484 * @retval None
2486 __weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi)
2488 /* Prevent unused argument(s) compilation warning */
2489 UNUSED(hspi);
2491 /* NOTE : This function should not be modified, when the callback is needed,
2492 the HAL_SPI_TxRxCpltCallback should be implemented in the user file
2497 * @brief Tx Half Transfer completed callback.
2498 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2499 * the configuration information for SPI module.
2500 * @retval None
2502 __weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2504 /* Prevent unused argument(s) compilation warning */
2505 UNUSED(hspi);
2507 /* NOTE : This function should not be modified, when the callback is needed,
2508 the HAL_SPI_TxHalfCpltCallback should be implemented in the user file
2513 * @brief Rx Half Transfer completed callback.
2514 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2515 * the configuration information for SPI module.
2516 * @retval None
2518 __weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2520 /* Prevent unused argument(s) compilation warning */
2521 UNUSED(hspi);
2523 /* NOTE : This function should not be modified, when the callback is needed,
2524 the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file
2529 * @brief Tx and Rx Half Transfer callback.
2530 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2531 * the configuration information for SPI module.
2532 * @retval None
2534 __weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2536 /* Prevent unused argument(s) compilation warning */
2537 UNUSED(hspi);
2539 /* NOTE : This function should not be modified, when the callback is needed,
2540 the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file
2545 * @brief SPI error callback.
2546 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2547 * the configuration information for SPI module.
2548 * @retval None
2550 __weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi)
2552 /* Prevent unused argument(s) compilation warning */
2553 UNUSED(hspi);
2555 /* NOTE : This function should not be modified, when the callback is needed,
2556 the HAL_SPI_ErrorCallback should be implemented in the user file
2558 /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes
2559 and user can use HAL_SPI_GetError() API to check the latest error occurred
2564 * @brief SPI Abort Complete callback.
2565 * @param hspi SPI handle.
2566 * @retval None
2568 __weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi)
2570 /* Prevent unused argument(s) compilation warning */
2571 UNUSED(hspi);
2573 /* NOTE : This function should not be modified, when the callback is needed,
2574 the HAL_SPI_AbortCpltCallback can be implemented in the user file.
2579 * @}
2582 /** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions
2583 * @brief SPI control functions
2585 @verbatim
2586 ===============================================================================
2587 ##### Peripheral State and Errors functions #####
2588 ===============================================================================
2589 [..]
2590 This subsection provides a set of functions allowing to control the SPI.
2591 (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral
2592 (+) HAL_SPI_GetError() check in run-time Errors occurring during communication
2593 @endverbatim
2594 * @{
2598 * @brief Return the SPI handle state.
2599 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2600 * the configuration information for SPI module.
2601 * @retval SPI state
2603 HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi)
2605 /* Return SPI handle state */
2606 return hspi->State;
2610 * @brief Return the SPI error code.
2611 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
2612 * the configuration information for SPI module.
2613 * @retval SPI error code in bitmap format
2615 uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi)
2617 /* Return SPI ErrorCode */
2618 return hspi->ErrorCode;
2622 * @}
2626 * @}
2629 /** @addtogroup SPI_Private_Functions
2630 * @brief Private functions
2631 * @{
2635 * @brief DMA SPI transmit process complete callback.
2636 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2637 * the configuration information for the specified DMA module.
2638 * @retval None
2640 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma)
2642 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2643 uint32_t tickstart = 0U;
2645 /* Init tickstart for timeout managment*/
2646 tickstart = HAL_GetTick();
2648 /* DMA Normal Mode */
2649 if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
2651 /* Disable ERR interrupt */
2652 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2654 /* Disable Tx DMA Request */
2655 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
2657 /* Check the end of the transaction */
2658 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2660 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2663 /* Clear overrun flag in 2 Lines communication mode because received data is not read */
2664 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
2666 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2669 hspi->TxXferCount = 0U;
2670 hspi->State = HAL_SPI_STATE_READY;
2672 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2674 HAL_SPI_ErrorCallback(hspi);
2675 return;
2678 HAL_SPI_TxCpltCallback(hspi);
2682 * @brief DMA SPI receive process complete callback.
2683 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2684 * the configuration information for the specified DMA module.
2685 * @retval None
2687 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
2689 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2690 uint32_t tickstart = 0U;
2691 #if (USE_SPI_CRC != 0U)
2692 __IO uint16_t tmpreg = 0U;
2693 #endif /* USE_SPI_CRC */
2695 /* Init tickstart for timeout management*/
2696 tickstart = HAL_GetTick();
2698 /* DMA Normal Mode */
2699 if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
2701 /* Disable ERR interrupt */
2702 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2704 #if (USE_SPI_CRC != 0U)
2705 /* CRC handling */
2706 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2708 /* Wait until RXNE flag */
2709 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2711 /* Error on the CRC reception */
2712 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2714 /* Read CRC */
2715 if (hspi->Init.DataSize > SPI_DATASIZE_8BIT)
2717 tmpreg = hspi->Instance->DR;
2718 /* To avoid GCC warning */
2719 UNUSED(tmpreg);
2721 else
2723 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2724 /* To avoid GCC warning */
2725 UNUSED(tmpreg);
2727 if (hspi->Init.CRCLength == SPI_CRC_LENGTH_16BIT)
2729 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2731 /* Error on the CRC reception */
2732 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2734 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2735 /* To avoid GCC warning */
2736 UNUSED(tmpreg);
2740 #endif /* USE_SPI_CRC */
2742 /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */
2743 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2745 /* Check the end of the transaction */
2746 if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2748 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
2751 hspi->RxXferCount = 0U;
2752 hspi->State = HAL_SPI_STATE_READY;
2754 #if (USE_SPI_CRC != 0U)
2755 /* Check if CRC error occurred */
2756 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2758 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2759 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2761 #endif /* USE_SPI_CRC */
2763 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2765 HAL_SPI_ErrorCallback(hspi);
2766 return;
2769 HAL_SPI_RxCpltCallback(hspi);
2773 * @brief DMA SPI transmit receive process complete callback.
2774 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2775 * the configuration information for the specified DMA module.
2776 * @retval None
2778 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2780 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2781 uint32_t tickstart = 0U;
2782 #if (USE_SPI_CRC != 0U)
2783 __IO int16_t tmpreg = 0U;
2784 #endif /* USE_SPI_CRC */
2785 /* Init tickstart for timeout management*/
2786 tickstart = HAL_GetTick();
2788 /* DMA Normal Mode */
2789 if ((hdma->Instance->CCR & DMA_CCR_CIRC) != DMA_CCR_CIRC)
2791 /* Disable ERR interrupt */
2792 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2794 #if (USE_SPI_CRC != 0U)
2795 /* CRC handling */
2796 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2798 if ((hspi->Init.DataSize == SPI_DATASIZE_8BIT) && (hspi->Init.CRCLength == SPI_CRC_LENGTH_8BIT))
2800 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_QUARTER_FULL, SPI_DEFAULT_TIMEOUT,
2801 tickstart) != HAL_OK)
2803 /* Error on the CRC reception */
2804 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2806 /* Read CRC to Flush DR and RXNE flag */
2807 tmpreg = *(__IO uint8_t *)&hspi->Instance->DR;
2808 /* To avoid GCC warning */
2809 UNUSED(tmpreg);
2811 else
2813 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_HALF_FULL, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2815 /* Error on the CRC reception */
2816 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2818 /* Read CRC to Flush DR and RXNE flag */
2819 tmpreg = hspi->Instance->DR;
2820 /* To avoid GCC warning */
2821 UNUSED(tmpreg);
2824 #endif /* USE_SPI_CRC */
2826 /* Check the end of the transaction */
2827 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2829 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2832 /* Disable Rx/Tx DMA Request */
2833 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2835 hspi->TxXferCount = 0U;
2836 hspi->RxXferCount = 0U;
2837 hspi->State = HAL_SPI_STATE_READY;
2839 #if (USE_SPI_CRC != 0U)
2840 /* Check if CRC error occurred */
2841 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2843 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2844 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2846 #endif /* USE_SPI_CRC */
2848 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2850 HAL_SPI_ErrorCallback(hspi);
2851 return;
2854 HAL_SPI_TxRxCpltCallback(hspi);
2858 * @brief DMA SPI half transmit process complete callback.
2859 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2860 * the configuration information for the specified DMA module.
2861 * @retval None
2863 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma)
2865 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2867 HAL_SPI_TxHalfCpltCallback(hspi);
2871 * @brief DMA SPI half receive process complete callback
2872 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2873 * the configuration information for the specified DMA module.
2874 * @retval None
2876 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma)
2878 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2880 HAL_SPI_RxHalfCpltCallback(hspi);
2884 * @brief DMA SPI half transmit receive process complete callback.
2885 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2886 * the configuration information for the specified DMA module.
2887 * @retval None
2889 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2891 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2893 HAL_SPI_TxRxHalfCpltCallback(hspi);
2897 * @brief DMA SPI communication error callback.
2898 * @param hdma pointer to a DMA_HandleTypeDef structure that contains
2899 * the configuration information for the specified DMA module.
2900 * @retval None
2902 static void SPI_DMAError(DMA_HandleTypeDef *hdma)
2904 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2906 /* Stop the disable DMA transfer on SPI side */
2907 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2909 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
2910 hspi->State = HAL_SPI_STATE_READY;
2911 HAL_SPI_ErrorCallback(hspi);
2915 * @brief DMA SPI communication abort callback, when initiated by HAL services on Error
2916 * (To be called at end of DMA Abort procedure following error occurrence).
2917 * @param hdma DMA handle.
2918 * @retval None
2920 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma)
2922 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2923 hspi->RxXferCount = 0U;
2924 hspi->TxXferCount = 0U;
2926 HAL_SPI_ErrorCallback(hspi);
2930 * @brief DMA SPI Tx communication abort callback, when initiated by user
2931 * (To be called at end of DMA Tx Abort procedure following user abort request).
2932 * @note When this callback is executed, User Abort complete call back is called only if no
2933 * Abort still ongoing for Rx DMA Handle.
2934 * @param hdma DMA handle.
2935 * @retval None
2937 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
2939 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
2941 hspi->hdmatx->XferAbortCallback = NULL;
2943 /* Disable Tx DMA Request */
2944 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
2946 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2948 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2951 /* Disable SPI Peripheral */
2952 __HAL_SPI_DISABLE(hspi);
2954 /* Empty the FRLVL fifo */
2955 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
2957 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
2960 /* Check if an Abort process is still ongoing */
2961 if (hspi->hdmarx != NULL)
2963 if (hspi->hdmarx->XferAbortCallback != NULL)
2965 return;
2969 /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
2970 hspi->RxXferCount = 0U;
2971 hspi->TxXferCount = 0U;
2973 /* Check no error during Abort procedure */
2974 if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
2976 /* Reset errorCode */
2977 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2980 /* Clear the Error flags in the SR register */
2981 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2982 __HAL_SPI_CLEAR_FREFLAG(hspi);
2984 /* Restore hspi->State to Ready */
2985 hspi->State = HAL_SPI_STATE_READY;
2987 /* Call user Abort complete callback */
2988 HAL_SPI_AbortCpltCallback(hspi);
2992 * @brief DMA SPI Rx communication abort callback, when initiated by user
2993 * (To be called at end of DMA Rx Abort procedure following user abort request).
2994 * @note When this callback is executed, User Abort complete call back is called only if no
2995 * Abort still ongoing for Tx DMA Handle.
2996 * @param hdma DMA handle.
2997 * @retval None
2999 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
3001 SPI_HandleTypeDef *hspi = (SPI_HandleTypeDef *)((DMA_HandleTypeDef *)hdma)->Parent;
3003 /* Disable SPI Peripheral */
3004 __HAL_SPI_DISABLE(hspi);
3006 hspi->hdmarx->XferAbortCallback = NULL;
3008 /* Disable Rx DMA Request */
3009 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
3011 /* Control the BSY flag */
3012 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3014 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3017 /* Empty the FRLVL fifo */
3018 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3020 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3023 /* Check if an Abort process is still ongoing */
3024 if (hspi->hdmatx != NULL)
3026 if (hspi->hdmatx->XferAbortCallback != NULL)
3028 return;
3032 /* No Abort process still ongoing : All DMA Stream/Channel are aborted, call user Abort Complete callback */
3033 hspi->RxXferCount = 0U;
3034 hspi->TxXferCount = 0U;
3036 /* Check no error during Abort procedure */
3037 if (hspi->ErrorCode != HAL_SPI_ERROR_ABORT)
3039 /* Reset errorCode */
3040 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
3043 /* Clear the Error flags in the SR register */
3044 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3045 __HAL_SPI_CLEAR_FREFLAG(hspi);
3047 /* Restore hspi->State to Ready */
3048 hspi->State = HAL_SPI_STATE_READY;
3050 /* Call user Abort complete callback */
3051 HAL_SPI_AbortCpltCallback(hspi);
3055 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
3056 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3057 * the configuration information for SPI module.
3058 * @retval None
3060 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3062 /* Receive data in packing mode */
3063 if (hspi->RxXferCount > 1U)
3065 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
3066 hspi->pRxBuffPtr += sizeof(uint16_t);
3067 hspi->RxXferCount -= 2U;
3068 if (hspi->RxXferCount == 1U)
3070 /* set fiforxthresold according the reception data length: 8bit */
3071 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
3074 /* Receive data in 8 Bit mode */
3075 else
3077 *hspi->pRxBuffPtr++ = *((__IO uint8_t *)&hspi->Instance->DR);
3078 hspi->RxXferCount--;
3081 /* check end of the reception */
3082 if (hspi->RxXferCount == 0U)
3084 #if (USE_SPI_CRC != 0U)
3085 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3087 SET_BIT(hspi->Instance->CR2, SPI_RXFIFO_THRESHOLD);
3088 hspi->RxISR = SPI_2linesRxISR_8BITCRC;
3089 return;
3091 #endif /* USE_SPI_CRC */
3093 /* Disable RXNE and ERR interrupt */
3094 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3096 if (hspi->TxXferCount == 0U)
3098 SPI_CloseRxTx_ISR(hspi);
3103 #if (USE_SPI_CRC != 0U)
3105 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
3106 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3107 * the configuration information for SPI module.
3108 * @retval None
3110 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
3112 __IO uint8_t tmpreg = 0U;
3114 /* Read data register to flush CRC */
3115 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3117 /* To avoid GCC warning */
3118 UNUSED(tmpreg);
3120 hspi->CRCSize--;
3122 /* check end of the reception */
3123 if (hspi->CRCSize == 0U)
3125 /* Disable RXNE and ERR interrupt */
3126 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3128 if (hspi->TxXferCount == 0U)
3130 SPI_CloseRxTx_ISR(hspi);
3134 #endif /* USE_SPI_CRC */
3137 * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode.
3138 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3139 * the configuration information for SPI module.
3140 * @retval None
3142 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3144 /* Transmit data in packing Bit mode */
3145 if (hspi->TxXferCount >= 2U)
3147 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3148 hspi->pTxBuffPtr += sizeof(uint16_t);
3149 hspi->TxXferCount -= 2U;
3151 /* Transmit data in 8 Bit mode */
3152 else
3154 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
3155 hspi->TxXferCount--;
3158 /* check the end of the transmission */
3159 if (hspi->TxXferCount == 0U)
3161 #if (USE_SPI_CRC != 0U)
3162 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3164 /* Set CRC Next Bit to send CRC */
3165 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3166 /* Disable TXE interrupt */
3167 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3168 return;
3170 #endif /* USE_SPI_CRC */
3172 /* Disable TXE interrupt */
3173 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3175 if (hspi->RxXferCount == 0U)
3177 SPI_CloseRxTx_ISR(hspi);
3183 * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode.
3184 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3185 * the configuration information for SPI module.
3186 * @retval None
3188 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3190 /* Receive data in 16 Bit mode */
3191 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
3192 hspi->pRxBuffPtr += sizeof(uint16_t);
3193 hspi->RxXferCount--;
3195 if (hspi->RxXferCount == 0U)
3197 #if (USE_SPI_CRC != 0U)
3198 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3200 hspi->RxISR = SPI_2linesRxISR_16BITCRC;
3201 return;
3203 #endif /* USE_SPI_CRC */
3205 /* Disable RXNE interrupt */
3206 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
3208 if (hspi->TxXferCount == 0U)
3210 SPI_CloseRxTx_ISR(hspi);
3215 #if (USE_SPI_CRC != 0U)
3217 * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode.
3218 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3219 * the configuration information for SPI module.
3220 * @retval None
3222 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
3224 /* Receive data in 16 Bit mode */
3225 __IO uint16_t tmpreg = 0U;
3227 /* Read data register to flush CRC */
3228 tmpreg = hspi->Instance->DR;
3230 /* To avoid GCC warning */
3231 UNUSED(tmpreg);
3233 /* Disable RXNE interrupt */
3234 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
3236 SPI_CloseRxTx_ISR(hspi);
3238 #endif /* USE_SPI_CRC */
3241 * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode.
3242 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3243 * the configuration information for SPI module.
3244 * @retval None
3246 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3248 /* Transmit data in 16 Bit mode */
3249 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3250 hspi->pTxBuffPtr += sizeof(uint16_t);
3251 hspi->TxXferCount--;
3253 /* Enable CRC Transmission */
3254 if (hspi->TxXferCount == 0U)
3256 #if (USE_SPI_CRC != 0U)
3257 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3259 /* Set CRC Next Bit to send CRC */
3260 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3261 /* Disable TXE interrupt */
3262 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3263 return;
3265 #endif /* USE_SPI_CRC */
3267 /* Disable TXE interrupt */
3268 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
3270 if (hspi->RxXferCount == 0U)
3272 SPI_CloseRxTx_ISR(hspi);
3277 #if (USE_SPI_CRC != 0U)
3279 * @brief Manage the CRC 8-bit receive in Interrupt context.
3280 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3281 * the configuration information for SPI module.
3282 * @retval None
3284 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
3286 __IO uint8_t tmpreg = 0U;
3288 /* Read data register to flush CRC */
3289 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3291 /* To avoid GCC warning */
3292 UNUSED(tmpreg);
3294 hspi->CRCSize--;
3296 if (hspi->CRCSize == 0U)
3298 SPI_CloseRx_ISR(hspi);
3301 #endif /* USE_SPI_CRC */
3304 * @brief Manage the receive 8-bit in Interrupt context.
3305 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3306 * the configuration information for SPI module.
3307 * @retval None
3309 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3311 *hspi->pRxBuffPtr++ = (*(__IO uint8_t *)&hspi->Instance->DR);
3312 hspi->RxXferCount--;
3314 #if (USE_SPI_CRC != 0U)
3315 /* Enable CRC Transmission */
3316 if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
3318 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3320 #endif /* USE_SPI_CRC */
3322 if (hspi->RxXferCount == 0U)
3324 #if (USE_SPI_CRC != 0U)
3325 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3327 hspi->RxISR = SPI_RxISR_8BITCRC;
3328 return;
3330 #endif /* USE_SPI_CRC */
3331 SPI_CloseRx_ISR(hspi);
3335 #if (USE_SPI_CRC != 0U)
3337 * @brief Manage the CRC 16-bit receive in Interrupt context.
3338 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3339 * the configuration information for SPI module.
3340 * @retval None
3342 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
3344 __IO uint16_t tmpreg = 0U;
3346 /* Read data register to flush CRC */
3347 tmpreg = hspi->Instance->DR;
3349 /* To avoid GCC warning */
3350 UNUSED(tmpreg);
3352 /* Disable RXNE and ERR interrupt */
3353 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3355 SPI_CloseRx_ISR(hspi);
3357 #endif /* USE_SPI_CRC */
3360 * @brief Manage the 16-bit receive in Interrupt context.
3361 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3362 * the configuration information for SPI module.
3363 * @retval None
3365 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3367 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
3368 hspi->pRxBuffPtr += sizeof(uint16_t);
3369 hspi->RxXferCount--;
3371 #if (USE_SPI_CRC != 0U)
3372 /* Enable CRC Transmission */
3373 if ((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
3375 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3377 #endif /* USE_SPI_CRC */
3379 if (hspi->RxXferCount == 0U)
3381 #if (USE_SPI_CRC != 0U)
3382 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3384 hspi->RxISR = SPI_RxISR_16BITCRC;
3385 return;
3387 #endif /* USE_SPI_CRC */
3388 SPI_CloseRx_ISR(hspi);
3393 * @brief Handle the data 8-bit transmit in Interrupt mode.
3394 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3395 * the configuration information for SPI module.
3396 * @retval None
3398 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
3400 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
3401 hspi->TxXferCount--;
3403 if (hspi->TxXferCount == 0U)
3405 #if (USE_SPI_CRC != 0U)
3406 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3408 /* Enable CRC Transmission */
3409 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3411 #endif /* USE_SPI_CRC */
3412 SPI_CloseTx_ISR(hspi);
3417 * @brief Handle the data 16-bit transmit in Interrupt mode.
3418 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3419 * the configuration information for SPI module.
3420 * @retval None
3422 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
3424 /* Transmit data in 16 Bit mode */
3425 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
3426 hspi->pTxBuffPtr += sizeof(uint16_t);
3427 hspi->TxXferCount--;
3429 if (hspi->TxXferCount == 0U)
3431 #if (USE_SPI_CRC != 0U)
3432 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3434 /* Enable CRC Transmission */
3435 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
3437 #endif /* USE_SPI_CRC */
3438 SPI_CloseTx_ISR(hspi);
3443 * @brief Handle SPI Communication Timeout.
3444 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3445 * the configuration information for SPI module.
3446 * @param Flag SPI flag to check
3447 * @param State flag state to check
3448 * @param Timeout Timeout duration
3449 * @param Tickstart tick start value
3450 * @retval HAL status
3452 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State,
3453 uint32_t Timeout, uint32_t Tickstart)
3455 while ((__HAL_SPI_GET_FLAG(hspi, Flag) ? SET : RESET) != State)
3457 if (Timeout != HAL_MAX_DELAY)
3459 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) >= Timeout))
3461 /* Disable the SPI and reset the CRC: the CRC value should be cleared
3462 on both master and slave sides in order to resynchronize the master
3463 and slave for their respective CRC calculation */
3465 /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
3466 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
3468 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3469 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3471 /* Disable SPI peripheral */
3472 __HAL_SPI_DISABLE(hspi);
3475 /* Reset CRC Calculation */
3476 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3478 SPI_RESET_CRC(hspi);
3481 hspi->State = HAL_SPI_STATE_READY;
3483 /* Process Unlocked */
3484 __HAL_UNLOCK(hspi);
3486 return HAL_TIMEOUT;
3491 return HAL_OK;
3495 * @brief Handle SPI FIFO Communication Timeout.
3496 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3497 * the configuration information for SPI module.
3498 * @param Fifo Fifo to check
3499 * @param State Fifo state to check
3500 * @param Timeout Timeout duration
3501 * @param Tickstart tick start value
3502 * @retval HAL status
3504 static HAL_StatusTypeDef SPI_WaitFifoStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Fifo, uint32_t State,
3505 uint32_t Timeout, uint32_t Tickstart)
3507 __IO uint8_t tmpreg;
3509 while ((hspi->Instance->SR & Fifo) != State)
3511 if ((Fifo == SPI_SR_FRLVL) && (State == SPI_FRLVL_EMPTY))
3513 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
3514 /* To avoid GCC warning */
3515 UNUSED(tmpreg);
3518 if (Timeout != HAL_MAX_DELAY)
3520 if ((Timeout == 0U) || ((HAL_GetTick() - Tickstart) >= Timeout))
3522 /* Disable the SPI and reset the CRC: the CRC value should be cleared
3523 on both master and slave sides in order to resynchronize the master
3524 and slave for their respective CRC calculation */
3526 /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
3527 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
3529 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3530 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3532 /* Disable SPI peripheral */
3533 __HAL_SPI_DISABLE(hspi);
3536 /* Reset CRC Calculation */
3537 if (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
3539 SPI_RESET_CRC(hspi);
3542 hspi->State = HAL_SPI_STATE_READY;
3544 /* Process Unlocked */
3545 __HAL_UNLOCK(hspi);
3547 return HAL_TIMEOUT;
3552 return HAL_OK;
3556 * @brief Handle the check of the RX transaction complete.
3557 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3558 * the configuration information for SPI module.
3559 * @param Timeout Timeout duration
3560 * @param Tickstart tick start value
3561 * @retval HAL status
3563 static HAL_StatusTypeDef SPI_EndRxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
3565 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3566 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3568 /* Disable SPI peripheral */
3569 __HAL_SPI_DISABLE(hspi);
3572 /* Control the BSY flag */
3573 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
3575 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3576 return HAL_TIMEOUT;
3579 if ((hspi->Init.Mode == SPI_MODE_MASTER) && ((hspi->Init.Direction == SPI_DIRECTION_1LINE)
3580 || (hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3582 /* Empty the FRLVL fifo */
3583 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3585 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3586 return HAL_TIMEOUT;
3589 return HAL_OK;
3593 * @brief Handle the check of the RXTX or TX transaction complete.
3594 * @param hspi SPI handle
3595 * @param Timeout Timeout duration
3596 * @param Tickstart tick start value
3597 * @retval HAL status
3599 static HAL_StatusTypeDef SPI_EndRxTxTransaction(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
3601 /* Control if the TX fifo is empty */
3602 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FTLVL, SPI_FTLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3604 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3605 return HAL_TIMEOUT;
3608 /* Control the BSY flag */
3609 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
3611 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3612 return HAL_TIMEOUT;
3615 /* Control if the RX fifo is empty */
3616 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, Timeout, Tickstart) != HAL_OK)
3618 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3619 return HAL_TIMEOUT;
3621 return HAL_OK;
3625 * @brief Handle the end of the RXTX transaction.
3626 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3627 * the configuration information for SPI module.
3628 * @retval None
3630 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi)
3632 uint32_t tickstart = 0U;
3634 /* Init tickstart for timeout managment*/
3635 tickstart = HAL_GetTick();
3637 /* Disable ERR interrupt */
3638 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
3640 /* Check the end of the transaction */
3641 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
3643 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3646 #if (USE_SPI_CRC != 0U)
3647 /* Check if CRC error occurred */
3648 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3650 hspi->State = HAL_SPI_STATE_READY;
3651 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3652 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3653 HAL_SPI_ErrorCallback(hspi);
3655 else
3657 #endif /* USE_SPI_CRC */
3658 if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3660 if (hspi->State == HAL_SPI_STATE_BUSY_RX)
3662 hspi->State = HAL_SPI_STATE_READY;
3663 HAL_SPI_RxCpltCallback(hspi);
3665 else
3667 hspi->State = HAL_SPI_STATE_READY;
3668 HAL_SPI_TxRxCpltCallback(hspi);
3671 else
3673 hspi->State = HAL_SPI_STATE_READY;
3674 HAL_SPI_ErrorCallback(hspi);
3676 #if (USE_SPI_CRC != 0U)
3678 #endif /* USE_SPI_CRC */
3682 * @brief Handle the end of the RX transaction.
3683 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3684 * the configuration information for SPI module.
3685 * @retval None
3687 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi)
3689 /* Disable RXNE and ERR interrupt */
3690 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3692 /* Check the end of the transaction */
3693 if (SPI_EndRxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3695 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3697 hspi->State = HAL_SPI_STATE_READY;
3699 #if (USE_SPI_CRC != 0U)
3700 /* Check if CRC error occurred */
3701 if (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3703 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3704 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3705 HAL_SPI_ErrorCallback(hspi);
3707 else
3709 #endif /* USE_SPI_CRC */
3710 if (hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3712 HAL_SPI_RxCpltCallback(hspi);
3714 else
3716 HAL_SPI_ErrorCallback(hspi);
3718 #if (USE_SPI_CRC != 0U)
3720 #endif /* USE_SPI_CRC */
3724 * @brief Handle the end of the TX transaction.
3725 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3726 * the configuration information for SPI module.
3727 * @retval None
3729 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi)
3731 uint32_t tickstart = 0U;
3733 /* Init tickstart for timeout management*/
3734 tickstart = HAL_GetTick();
3736 /* Disable TXE and ERR interrupt */
3737 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
3739 /* Check the end of the transaction */
3740 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
3742 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3745 /* Clear overrun flag in 2 Lines communication mode because received is not read */
3746 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
3748 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3751 hspi->State = HAL_SPI_STATE_READY;
3752 if (hspi->ErrorCode != HAL_SPI_ERROR_NONE)
3754 HAL_SPI_ErrorCallback(hspi);
3756 else
3758 HAL_SPI_TxCpltCallback(hspi);
3763 * @brief Handle abort a Rx transaction.
3764 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3765 * the configuration information for SPI module.
3766 * @retval None
3768 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi)
3770 __IO uint32_t count;
3772 /* Disable SPI Peripheral */
3773 __HAL_SPI_DISABLE(hspi);
3775 count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
3777 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3778 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3780 /* Check RXNEIE is disabled */
3783 if (count-- == 0U)
3785 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
3786 break;
3789 while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE));
3791 /* Control the BSY flag */
3792 if (SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3794 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3797 /* Empty the FRLVL fifo */
3798 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3800 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3803 hspi->State = HAL_SPI_STATE_ABORT;
3807 * @brief Handle abort a Tx or Rx/Tx transaction.
3808 * @param hspi pointer to a SPI_HandleTypeDef structure that contains
3809 * the configuration information for SPI module.
3810 * @retval None
3812 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi)
3814 __IO uint32_t count;
3816 count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
3818 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3819 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3821 /* Check TXEIE is disabled */
3824 if (count-- == 0U)
3826 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_ABORT);
3827 break;
3830 while (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE));
3832 if (SPI_EndRxTxTransaction(hspi, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3834 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3837 /* Disable SPI Peripheral */
3838 __HAL_SPI_DISABLE(hspi);
3840 /* Empty the FRLVL fifo */
3841 if (SPI_WaitFifoStateUntilTimeout(hspi, SPI_FLAG_FRLVL, SPI_FRLVL_EMPTY, SPI_DEFAULT_TIMEOUT, HAL_GetTick()) != HAL_OK)
3843 hspi->ErrorCode = HAL_SPI_ERROR_ABORT;
3846 hspi->State = HAL_SPI_STATE_ABORT;
3850 * @}
3853 #endif /* HAL_SPI_MODULE_ENABLED */
3856 * @}
3860 * @}
3863 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/