Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / lib / main / STM32F4 / Drivers / STM32F4xx_HAL_Driver / Src / stm32f4xx_hal_spi.c
blob7bfe61b76f105d67a08f3f25ebe4626a63ce6235
1 /**
2 ******************************************************************************
3 * @file stm32f4xx_hal_spi.c
4 * @author MCD Application Team
5 * @version V1.7.1
6 * @date 14-April-2017
7 * @brief SPI HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Serial Peripheral Interface (SPI) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
13 * + Peripheral State functions
15 @verbatim
16 ==============================================================================
17 ##### How to use this driver #####
18 ==============================================================================
19 [..]
20 The SPI HAL driver can be used as follows:
22 (#) Declare a SPI_HandleTypeDef handle structure, for example:
23 SPI_HandleTypeDef hspi;
25 (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API:
26 (##) Enable the SPIx interface clock
27 (##) SPI pins configuration
28 (+++) Enable the clock for the SPI GPIOs
29 (+++) Configure these SPI pins as alternate function push-pull
30 (##) NVIC configuration if you need to use interrupt process
31 (+++) Configure the SPIx interrupt priority
32 (+++) Enable the NVIC SPI IRQ handle
33 (##) DMA Configuration if you need to use DMA process
34 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive stream
35 (+++) Enable the DMAx clock
36 (+++) Configure the DMA handle parameters
37 (+++) Configure the DMA Tx or Rx stream
38 (+++) Associate the initialized hdma_tx handle to the hspi DMA Tx or Rx handle
39 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx stream
41 (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS
42 management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure.
44 (#) Initialize the SPI registers by calling the HAL_SPI_Init() API:
45 (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
46 by calling the customized HAL_SPI_MspInit() API.
47 [..]
48 Circular mode restriction:
49 (#) The DMA circular mode cannot be used when the SPI is configured in these modes:
50 (##) Master 2Lines RxOnly
51 (##) Master 1Line Rx
52 (#) The CRC feature is not managed when the DMA circular mode is enabled
53 (#) When the SPI DMA Pause/Stop features are used, we must use the following APIs
54 the HAL_SPI_DMAPause()/ HAL_SPI_DMAStop() only under the SPI callbacks
55 [..]
56 Master Receive mode restriction:
57 (#) In Master unidirectional receive-only mode (MSTR =1, BIDIMODE=0, RXONLY=0) or
58 bidirectional receive mode (MSTR=1, BIDIMODE=1, BIDIOE=0), to ensure that the SPI
59 does not initiate a new transfer the following procedure has to be respected:
60 (##) HAL_SPI_DeInit()
61 (##) HAL_SPI_Init()
63 @endverbatim
65 Using the HAL it is not possible to reach all supported SPI frequency with the differents SPI Modes,
66 the following tables resume the max SPI frequency reached with data size 8bits/16bits,
67 according to frequency used on APBx Peripheral Clock (fPCLK) used by the SPI instance :
69 DataSize = SPI_DATASIZE_8BIT:
70 +----------------------------------------------------------------------------------------------+
71 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
72 | Process | Tranfert mode |---------------------|----------------------|----------------------|
73 | | | Master | Slave | Master | Slave | Master | Slave |
74 |==============================================================================================|
75 | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
76 | X |----------------|----------|----------|-----------|----------|-----------|----------|
77 | / | Interrupt | Fpclk/4 | Fpclk/8 | NA | NA | NA | NA |
78 | R |----------------|----------|----------|-----------|----------|-----------|----------|
79 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
80 |=========|================|==========|==========|===========|==========|===========|==========|
81 | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 |
82 | |----------------|----------|----------|-----------|----------|-----------|----------|
83 | R | Interrupt | Fpclk/8 | Fpclk/8 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 |
84 | X |----------------|----------|----------|-----------|----------|-----------|----------|
85 | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 |
86 |=========|================|==========|==========|===========|==========|===========|==========|
87 | | Polling | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 |
88 | |----------------|----------|----------|-----------|----------|-----------|----------|
89 | T | Interrupt | Fpclk/2 | Fpclk/4 | NA | NA | Fpclk/2 | Fpclk/64 |
90 | X |----------------|----------|----------|-----------|----------|-----------|----------|
91 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128|
92 +----------------------------------------------------------------------------------------------+
94 DataSize = SPI_DATASIZE_16BIT:
95 +----------------------------------------------------------------------------------------------+
96 | | | 2Lines Fullduplex | 2Lines RxOnly | 1Line |
97 | Process | Tranfert mode |---------------------|----------------------|----------------------|
98 | | | Master | Slave | Master | Slave | Master | Slave |
99 |==============================================================================================|
100 | T | Polling | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
101 | X |----------------|----------|----------|-----------|----------|-----------|----------|
102 | / | Interrupt | Fpclk/4 | Fpclk/4 | NA | NA | NA | NA |
103 | R |----------------|----------|----------|-----------|----------|-----------|----------|
104 | X | DMA | Fpclk/2 | Fpclk/2 | NA | NA | NA | NA |
105 |=========|================|==========|==========|===========|==========|===========|==========|
106 | | Polling | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/32 | Fpclk/2 |
107 | |----------------|----------|----------|-----------|----------|-----------|----------|
108 | R | Interrupt | Fpclk/4 | Fpclk/4 | Fpclk/64 | Fpclk/2 | Fpclk/64 | Fpclk/2 |
109 | X |----------------|----------|----------|-----------|----------|-----------|----------|
110 | | DMA | Fpclk/2 | Fpclk/2 | Fpclk/64 | Fpclk/2 | Fpclk/128 | Fpclk/2 |
111 |=========|================|==========|==========|===========|==========|===========|==========|
112 | | Polling | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/32 |
113 | |----------------|----------|----------|-----------|----------|-----------|----------|
114 | T | Interrupt | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/64 |
115 | X |----------------|----------|----------|-----------|----------|-----------|----------|
116 | | DMA | Fpclk/2 | Fpclk/2 | NA | NA | Fpclk/2 | Fpclk/128|
117 +----------------------------------------------------------------------------------------------+
118 [..]
119 (@) The max SPI frequency depend on SPI data size (8bits, 16bits),
120 SPI mode(2 Lines fullduplex, 2 lines RxOnly, 1 line TX/RX) and Process mode (Polling, IT, DMA).
122 (+@) TX/RX processes are HAL_SPI_TransmitReceive(), HAL_SPI_TransmitReceive_IT() and HAL_SPI_TransmitReceive_DMA()
123 (+@) RX processes are HAL_SPI_Receive(), HAL_SPI_Receive_IT() and HAL_SPI_Receive_DMA()
124 (+@) TX processes are HAL_SPI_Transmit(), HAL_SPI_Transmit_IT() and HAL_SPI_Transmit_DMA()
125 ******************************************************************************
126 * @attention
128 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
130 * Redistribution and use in source and binary forms, with or without modification,
131 * are permitted provided that the following conditions are met:
132 * 1. Redistributions of source code must retain the above copyright notice,
133 * this list of conditions and the following disclaimer.
134 * 2. Redistributions in binary form must reproduce the above copyright notice,
135 * this list of conditions and the following disclaimer in the documentation
136 * and/or other materials provided with the distribution.
137 * 3. Neither the name of STMicroelectronics nor the names of its contributors
138 * may be used to endorse or promote products derived from this software
139 * without specific prior written permission.
141 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
142 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
143 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
144 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
145 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
146 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
147 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
148 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
149 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
150 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
152 ******************************************************************************
155 /* Includes ------------------------------------------------------------------*/
156 #include "stm32f4xx_hal.h"
158 /** @addtogroup STM32F4xx_HAL_Driver
159 * @{
161 /** @defgroup SPI SPI
162 * @brief SPI HAL module driver
163 * @{
165 #ifdef HAL_SPI_MODULE_ENABLED
167 /* Private typedef -----------------------------------------------------------*/
168 /* Private defines -----------------------------------------------------------*/
169 /** @defgroup SPI_Private_Constants SPI Private Constants
170 * @{
172 #define SPI_DEFAULT_TIMEOUT 100U
174 * @}
177 /* Private macros ------------------------------------------------------------*/
178 /* Private variables ---------------------------------------------------------*/
179 /* Private function prototypes -----------------------------------------------*/
180 /** @addtogroup SPI_Private_Functions
181 * @{
183 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma);
184 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
185 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma);
186 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma);
187 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma);
188 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma);
189 static void SPI_DMAError(DMA_HandleTypeDef *hdma);
190 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma);
191 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
192 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
193 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State, uint32_t Timeout, uint32_t Tickstart);
194 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
195 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
196 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
197 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
198 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
199 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi);
200 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
201 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi);
202 #if (USE_SPI_CRC != 0U)
203 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
204 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
205 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi);
206 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi);
207 #endif /* USE_SPI_CRC */
208 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi);
209 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi);
210 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi);
211 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi);
212 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi);
213 static HAL_StatusTypeDef SPI_CheckFlag_BSY(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart);
215 * @}
218 /* Exported functions --------------------------------------------------------*/
219 /** @defgroup SPI_Exported_Functions SPI Exported Functions
220 * @{
223 /** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions
224 * @brief Initialization and Configuration functions
226 @verbatim
227 ===============================================================================
228 ##### Initialization and de-initialization functions #####
229 ===============================================================================
230 [..] This subsection provides a set of functions allowing to initialize and
231 de-initialize the SPIx peripheral:
233 (+) User must implement HAL_SPI_MspInit() function in which he configures
234 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
236 (+) Call the function HAL_SPI_Init() to configure the selected device with
237 the selected configuration:
238 (++) Mode
239 (++) Direction
240 (++) Data Size
241 (++) Clock Polarity and Phase
242 (++) NSS Management
243 (++) BaudRate Prescaler
244 (++) FirstBit
245 (++) TIMode
246 (++) CRC Calculation
247 (++) CRC Polynomial if CRC enabled
249 (+) Call the function HAL_SPI_DeInit() to restore the default configuration
250 of the selected SPIx peripheral.
252 @endverbatim
253 * @{
257 * @brief Initialize the SPI according to the specified parameters
258 * in the SPI_InitTypeDef and initialize the associated handle.
259 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
260 * the configuration information for SPI module.
261 * @retval HAL status
263 HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi)
265 /* Check the SPI handle allocation */
266 if(hspi == NULL)
268 return HAL_ERROR;
271 /* Check the parameters */
272 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
273 assert_param(IS_SPI_MODE(hspi->Init.Mode));
274 assert_param(IS_SPI_DIRECTION(hspi->Init.Direction));
275 assert_param(IS_SPI_DATASIZE(hspi->Init.DataSize));
276 assert_param(IS_SPI_NSS(hspi->Init.NSS));
277 assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi->Init.BaudRatePrescaler));
278 assert_param(IS_SPI_FIRST_BIT(hspi->Init.FirstBit));
279 assert_param(IS_SPI_TIMODE(hspi->Init.TIMode));
280 if(hspi->Init.TIMode == SPI_TIMODE_DISABLE)
282 assert_param(IS_SPI_CPOL(hspi->Init.CLKPolarity));
283 assert_param(IS_SPI_CPHA(hspi->Init.CLKPhase));
285 #if (USE_SPI_CRC != 0U)
286 assert_param(IS_SPI_CRC_CALCULATION(hspi->Init.CRCCalculation));
287 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
289 assert_param(IS_SPI_CRC_POLYNOMIAL(hspi->Init.CRCPolynomial));
291 #else
292 hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
293 #endif /* USE_SPI_CRC */
295 if(hspi->State == HAL_SPI_STATE_RESET)
297 /* Allocate lock resource and initialize it */
298 hspi->Lock = HAL_UNLOCKED;
300 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
301 HAL_SPI_MspInit(hspi);
304 hspi->State = HAL_SPI_STATE_BUSY;
306 /* Disable the selected SPI peripheral */
307 __HAL_SPI_DISABLE(hspi);
309 /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/
310 /* Configure : SPI Mode, Communication Mode, Data size, Clock polarity and phase, NSS management,
311 Communication speed, First bit and CRC calculation state */
312 WRITE_REG(hspi->Instance->CR1, (hspi->Init.Mode | hspi->Init.Direction | hspi->Init.DataSize |
313 hspi->Init.CLKPolarity | hspi->Init.CLKPhase | (hspi->Init.NSS & SPI_CR1_SSM) |
314 hspi->Init.BaudRatePrescaler | hspi->Init.FirstBit | hspi->Init.CRCCalculation) );
316 /* Configure : NSS management */
317 WRITE_REG(hspi->Instance->CR2, (((hspi->Init.NSS >> 16U) & SPI_CR2_SSOE) | hspi->Init.TIMode));
319 #if (USE_SPI_CRC != 0U)
320 /*---------------------------- SPIx CRCPOLY Configuration ------------------*/
321 /* Configure : CRC Polynomial */
322 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
324 WRITE_REG(hspi->Instance->CRCPR, hspi->Init.CRCPolynomial);
326 #endif /* USE_SPI_CRC */
328 #if defined(SPI_I2SCFGR_I2SMOD)
329 /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */
330 CLEAR_BIT(hspi->Instance->I2SCFGR, SPI_I2SCFGR_I2SMOD);
331 #endif /* USE_SPI_CRC */
333 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
334 hspi->State = HAL_SPI_STATE_READY;
336 return HAL_OK;
340 * @brief De Initialize the SPI peripheral.
341 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
342 * the configuration information for SPI module.
343 * @retval HAL status
345 HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi)
347 /* Check the SPI handle allocation */
348 if(hspi == NULL)
350 return HAL_ERROR;
353 /* Check SPI Instance parameter */
354 assert_param(IS_SPI_ALL_INSTANCE(hspi->Instance));
356 hspi->State = HAL_SPI_STATE_BUSY;
358 /* Disable the SPI Peripheral Clock */
359 __HAL_SPI_DISABLE(hspi);
361 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
362 HAL_SPI_MspDeInit(hspi);
364 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
365 hspi->State = HAL_SPI_STATE_RESET;
367 /* Release Lock */
368 __HAL_UNLOCK(hspi);
370 return HAL_OK;
374 * @brief Initialize the SPI MSP.
375 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
376 * the configuration information for SPI module.
377 * @retval None
379 __weak void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
381 /* Prevent unused argument(s) compilation warning */
382 UNUSED(hspi);
383 /* NOTE : This function should not be modified, when the callback is needed,
384 the HAL_SPI_MspInit should be implemented in the user file
389 * @brief De-Initialize the SPI MSP.
390 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
391 * the configuration information for SPI module.
392 * @retval None
394 __weak void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi)
396 /* Prevent unused argument(s) compilation warning */
397 UNUSED(hspi);
398 /* NOTE : This function should not be modified, when the callback is needed,
399 the HAL_SPI_MspDeInit should be implemented in the user file
404 * @}
407 /** @defgroup SPI_Exported_Functions_Group2 IO operation functions
408 * @brief Data transfers functions
410 @verbatim
411 ==============================================================================
412 ##### IO operation functions #####
413 ===============================================================================
414 [..]
415 This subsection provides a set of functions allowing to manage the SPI
416 data transfers.
418 [..] The SPI supports master and slave mode :
420 (#) There are two modes of transfer:
421 (++) Blocking mode: The communication is performed in polling mode.
422 The HAL status of all data processing is returned by the same function
423 after finishing transfer.
424 (++) No-Blocking mode: The communication is performed using Interrupts
425 or DMA, These APIs return the HAL status.
426 The end of the data processing will be indicated through the
427 dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when
428 using DMA mode.
429 The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks
430 will be executed respectively at the end of the transmit or Receive process
431 The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected
433 (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA)
434 exist for 1Line (simplex) and 2Lines (full duplex) modes.
436 @endverbatim
437 * @{
441 * @brief Transmit an amount of data in blocking mode.
442 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
443 * the configuration information for SPI module.
444 * @param pData: pointer to data buffer
445 * @param Size: amount of data to be sent
446 * @param Timeout: Timeout duration
447 * @retval HAL status
449 HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
451 uint32_t tickstart = 0U;
452 HAL_StatusTypeDef errorcode = HAL_OK;
454 /* Check Direction parameter */
455 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
457 /* Process Locked */
458 __HAL_LOCK(hspi);
460 /* Init tickstart for timeout management*/
461 tickstart = HAL_GetTick();
463 if(hspi->State != HAL_SPI_STATE_READY)
465 errorcode = HAL_BUSY;
466 goto error;
469 if((pData == NULL ) || (Size == 0))
471 errorcode = HAL_ERROR;
472 goto error;
475 /* Set the transaction information */
476 hspi->State = HAL_SPI_STATE_BUSY_TX;
477 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
478 hspi->pTxBuffPtr = (uint8_t *)pData;
479 hspi->TxXferSize = Size;
480 hspi->TxXferCount = Size;
482 /*Init field not used in handle to zero */
483 hspi->pRxBuffPtr = (uint8_t *)NULL;
484 hspi->RxXferSize = 0U;
485 hspi->RxXferCount = 0U;
486 hspi->TxISR = NULL;
487 hspi->RxISR = NULL;
489 /* Configure communication direction : 1Line */
490 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
492 SPI_1LINE_TX(hspi);
495 #if (USE_SPI_CRC != 0U)
496 /* Reset CRC Calculation */
497 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
499 SPI_RESET_CRC(hspi);
501 #endif /* USE_SPI_CRC */
503 /* Check if the SPI is already enabled */
504 if((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
506 /* Enable SPI peripheral */
507 __HAL_SPI_ENABLE(hspi);
510 /* Transmit data in 16 Bit mode */
511 if(hspi->Init.DataSize == SPI_DATASIZE_16BIT)
513 if((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01))
515 hspi->Instance->DR = *((uint16_t *)pData);
516 pData += sizeof(uint16_t);
517 hspi->TxXferCount--;
519 /* Transmit data in 16 Bit mode */
520 while (hspi->TxXferCount > 0U)
522 /* Wait until TXE flag is set to send data */
523 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
525 hspi->Instance->DR = *((uint16_t *)pData);
526 pData += sizeof(uint16_t);
527 hspi->TxXferCount--;
529 else
531 /* Timeout management */
532 if((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout)))
534 errorcode = HAL_TIMEOUT;
535 goto error;
540 /* Transmit data in 8 Bit mode */
541 else
543 if((hspi->Init.Mode == SPI_MODE_SLAVE)|| (hspi->TxXferCount == 0x01))
545 *((__IO uint8_t*)&hspi->Instance->DR) = (*pData);
546 pData += sizeof(uint8_t);
547 hspi->TxXferCount--;
549 while (hspi->TxXferCount > 0U)
551 /* Wait until TXE flag is set to send data */
552 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE))
554 *((__IO uint8_t*)&hspi->Instance->DR) = (*pData);
555 pData += sizeof(uint8_t);
556 hspi->TxXferCount--;
558 else
560 /* Timeout management */
561 if((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout)))
563 errorcode = HAL_TIMEOUT;
564 goto error;
570 /* Wait until TXE flag */
571 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_TXE, SET, Timeout, tickstart) != HAL_OK)
573 errorcode = HAL_TIMEOUT;
574 goto error;
577 /* Check Busy flag */
578 if(SPI_CheckFlag_BSY(hspi, Timeout, tickstart) != HAL_OK)
580 errorcode = HAL_ERROR;
581 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
582 goto error;
585 /* Clear overrun flag in 2 Lines communication mode because received is not read */
586 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
588 __HAL_SPI_CLEAR_OVRFLAG(hspi);
590 #if (USE_SPI_CRC != 0U)
591 /* Enable CRC Transmission */
592 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
594 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
596 #endif /* USE_SPI_CRC */
598 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
600 errorcode = HAL_ERROR;
603 error:
604 hspi->State = HAL_SPI_STATE_READY;
605 /* Process Unlocked */
606 __HAL_UNLOCK(hspi);
607 return errorcode;
611 * @brief Receive an amount of data in blocking mode.
612 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
613 * the configuration information for SPI module.
614 * @param pData: pointer to data buffer
615 * @param Size: amount of data to be received
616 * @param Timeout: Timeout duration
617 * @retval HAL status
619 HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout)
621 #if (USE_SPI_CRC != 0U)
622 __IO uint16_t tmpreg = 0U;
623 #endif /* USE_SPI_CRC */
624 uint32_t tickstart = 0U;
625 HAL_StatusTypeDef errorcode = HAL_OK;
627 if((hspi->Init.Mode == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES))
629 hspi->State = HAL_SPI_STATE_BUSY_RX;
630 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
631 return HAL_SPI_TransmitReceive(hspi,pData,pData,Size,Timeout);
634 /* Process Locked */
635 __HAL_LOCK(hspi);
637 /* Init tickstart for timeout management*/
638 tickstart = HAL_GetTick();
640 if(hspi->State != HAL_SPI_STATE_READY)
642 errorcode = HAL_BUSY;
643 goto error;
646 if((pData == NULL ) || (Size == 0))
648 errorcode = HAL_ERROR;
649 goto error;
652 /* Set the transaction information */
653 hspi->State = HAL_SPI_STATE_BUSY_RX;
654 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
655 hspi->pRxBuffPtr = (uint8_t *)pData;
656 hspi->RxXferSize = Size;
657 hspi->RxXferCount = Size;
659 /*Init field not used in handle to zero */
660 hspi->pTxBuffPtr = (uint8_t *)NULL;
661 hspi->TxXferSize = 0U;
662 hspi->TxXferCount = 0U;
663 hspi->RxISR = NULL;
664 hspi->TxISR = NULL;
666 #if (USE_SPI_CRC != 0U)
667 /* Reset CRC Calculation */
668 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
670 SPI_RESET_CRC(hspi);
671 /* this is done to handle the CRCNEXT before the latest data */
672 hspi->RxXferCount--;
674 #endif /* USE_SPI_CRC */
676 /* Configure communication direction: 1Line */
677 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
679 SPI_1LINE_RX(hspi);
682 /* Check if the SPI is already enabled */
683 if((hspi->Instance->CR1 & SPI_CR1_SPE) != SPI_CR1_SPE)
685 /* Enable SPI peripheral */
686 __HAL_SPI_ENABLE(hspi);
689 /* Receive data in 8 Bit mode */
690 if(hspi->Init.DataSize == SPI_DATASIZE_8BIT)
692 /* Transfer loop */
693 while(hspi->RxXferCount > 0U)
695 /* Check the RXNE flag */
696 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
698 /* read the received data */
699 (* (uint8_t *)pData)= *(__IO uint8_t *)&hspi->Instance->DR;
700 pData += sizeof(uint8_t);
701 hspi->RxXferCount--;
703 else
705 /* Timeout management */
706 if((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout)))
708 errorcode = HAL_TIMEOUT;
709 goto error;
714 else
716 /* Transfer loop */
717 while(hspi->RxXferCount > 0U)
719 /* Check the RXNE flag */
720 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE))
722 *((uint16_t*)pData) = hspi->Instance->DR;
723 pData += sizeof(uint16_t);
724 hspi->RxXferCount--;
726 else
728 /* Timeout management */
729 if((Timeout == 0U) || ((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout)))
731 errorcode = HAL_TIMEOUT;
732 goto error;
738 #if (USE_SPI_CRC != 0U)
739 /* Handle the CRC Transmission */
740 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
742 /* freeze the CRC before the latest data */
743 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
745 /* Read the latest data */
746 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
748 /* the latest data has not been received */
749 errorcode = HAL_TIMEOUT;
750 goto error;
753 /* Receive last data in 16 Bit mode */
754 if(hspi->Init.DataSize == SPI_DATASIZE_16BIT)
756 *((uint16_t*)pData) = hspi->Instance->DR;
758 /* Receive last data in 8 Bit mode */
759 else
761 (*(uint8_t *)pData) = *(__IO uint8_t *)&hspi->Instance->DR;
764 /* Wait the CRC data */
765 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
767 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
768 errorcode = HAL_TIMEOUT;
769 goto error;
772 /* Read CRC to Flush DR and RXNE flag */
773 tmpreg = hspi->Instance->DR;
774 /* To avoid GCC warning */
775 UNUSED(tmpreg);
777 #endif /* USE_SPI_CRC */
779 /* Check the end of the transaction */
780 if((hspi->Init.Mode == SPI_MODE_MASTER)&&((hspi->Init.Direction == SPI_DIRECTION_1LINE)||(hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
782 /* Disable SPI peripheral */
783 __HAL_SPI_DISABLE(hspi);
786 #if (USE_SPI_CRC != 0U)
787 /* Check if CRC error occurred */
788 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
790 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
791 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
793 #endif /* USE_SPI_CRC */
795 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
797 errorcode = HAL_ERROR;
800 error :
801 hspi->State = HAL_SPI_STATE_READY;
802 __HAL_UNLOCK(hspi);
803 return errorcode;
807 * @brief Transmit and Receive an amount of data in blocking mode.
808 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
809 * the configuration information for SPI module.
810 * @param pTxData: pointer to transmission data buffer
811 * @param pRxData: pointer to reception data buffer
812 * @param Size: amount of data to be sent and received
813 * @param Timeout: Timeout duration
814 * @retval HAL status
816 HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
818 uint32_t tmp = 0U, tmp1 = 0U;
819 #if (USE_SPI_CRC != 0U)
820 __IO uint16_t tmpreg1 = 0U;
821 #endif /* USE_SPI_CRC */
822 uint32_t tickstart = 0U;
823 /* Variable used to alternate Rx and Tx during transfer */
824 uint32_t txallowed = 1U;
825 HAL_StatusTypeDef errorcode = HAL_OK;
827 /* Check Direction parameter */
828 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
830 /* Process Locked */
831 __HAL_LOCK(hspi);
833 /* Init tickstart for timeout management*/
834 tickstart = HAL_GetTick();
836 tmp = hspi->State;
837 tmp1 = hspi->Init.Mode;
839 if(!((tmp == HAL_SPI_STATE_READY) || \
840 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
842 errorcode = HAL_BUSY;
843 goto error;
846 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0))
848 errorcode = HAL_ERROR;
849 goto error;
852 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
853 if(hspi->State == HAL_SPI_STATE_READY)
855 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
858 /* Set the transaction information */
859 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
860 hspi->pRxBuffPtr = (uint8_t *)pRxData;
861 hspi->RxXferCount = Size;
862 hspi->RxXferSize = Size;
863 hspi->pTxBuffPtr = (uint8_t *)pTxData;
864 hspi->TxXferCount = Size;
865 hspi->TxXferSize = Size;
867 /*Init field not used in handle to zero */
868 hspi->RxISR = NULL;
869 hspi->TxISR = NULL;
871 #if (USE_SPI_CRC != 0U)
872 /* Reset CRC Calculation */
873 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
875 SPI_RESET_CRC(hspi);
877 #endif /* USE_SPI_CRC */
879 /* Check if the SPI is already enabled */
880 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
882 /* Enable SPI peripheral */
883 __HAL_SPI_ENABLE(hspi);
886 /* Transmit and Receive data in 16 Bit mode */
887 if(hspi->Init.DataSize == SPI_DATASIZE_16BIT)
889 if((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
891 hspi->Instance->DR = *((uint16_t *)pTxData);
892 pTxData += sizeof(uint16_t);
893 hspi->TxXferCount--;
895 while ((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
897 /* Check TXE flag */
898 if(txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
900 hspi->Instance->DR = *((uint16_t *)pTxData);
901 pTxData += sizeof(uint16_t);
902 hspi->TxXferCount--;
903 /* Next Data is a reception (Rx). Tx not allowed */
904 txallowed = 0U;
906 #if (USE_SPI_CRC != 0U)
907 /* Enable CRC Transmission */
908 if((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
910 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
912 #endif /* USE_SPI_CRC */
915 /* Check RXNE flag */
916 if((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
918 *((uint16_t *)pRxData) = hspi->Instance->DR;
919 pRxData += sizeof(uint16_t);
920 hspi->RxXferCount--;
921 /* Next Data is a Transmission (Tx). Tx is allowed */
922 txallowed = 1U;
924 if((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout))
926 errorcode = HAL_TIMEOUT;
927 goto error;
931 /* Transmit and Receive data in 8 Bit mode */
932 else
934 if((hspi->Init.Mode == SPI_MODE_SLAVE) || (hspi->TxXferCount == 0x01U))
936 *((__IO uint8_t*)&hspi->Instance->DR) = (*pTxData);
937 pTxData += sizeof(uint8_t);
938 hspi->TxXferCount--;
940 while((hspi->TxXferCount > 0U) || (hspi->RxXferCount > 0U))
942 /* check TXE flag */
943 if(txallowed && (hspi->TxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_TXE)))
945 *(__IO uint8_t *)&hspi->Instance->DR = (*pTxData++);
946 hspi->TxXferCount--;
947 /* Next Data is a reception (Rx). Tx not allowed */
948 txallowed = 0U;
950 #if (USE_SPI_CRC != 0U)
951 /* Enable CRC Transmission */
952 if((hspi->TxXferCount == 0U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
954 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
956 #endif /* USE_SPI_CRC */
959 /* Wait until RXNE flag is reset */
960 if((hspi->RxXferCount > 0U) && (__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_RXNE)))
962 (*(uint8_t *)pRxData++) = hspi->Instance->DR;
963 hspi->RxXferCount--;
964 /* Next Data is a Transmission (Tx). Tx is allowed */
965 txallowed = 1U;
967 if((Timeout != HAL_MAX_DELAY) && ((HAL_GetTick()-tickstart) >= Timeout))
969 errorcode = HAL_TIMEOUT;
970 goto error;
975 #if (USE_SPI_CRC != 0U)
976 /* Read CRC from DR to close CRC calculation process */
977 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
979 /* Wait until TXE flag */
980 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, Timeout, tickstart) != HAL_OK)
982 /* Error on the CRC reception */
983 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
984 errorcode = HAL_TIMEOUT;
985 goto error;
987 /* Read CRC */
988 tmpreg1 = hspi->Instance->DR;
989 /* To avoid GCC warning */
990 UNUSED(tmpreg1);
993 /* Check if CRC error occurred */
994 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
996 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
997 /* Clear CRC Flag */
998 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
1000 errorcode = HAL_ERROR;
1002 #endif /* USE_SPI_CRC */
1004 /* Wait until TXE flag */
1005 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_TXE, SET, Timeout, tickstart) != HAL_OK)
1007 errorcode = HAL_TIMEOUT;
1008 goto error;
1011 /* Check Busy flag */
1012 if(SPI_CheckFlag_BSY(hspi, Timeout, tickstart) != HAL_OK)
1014 errorcode = HAL_ERROR;
1015 hspi->ErrorCode = HAL_SPI_ERROR_FLAG;
1016 goto error;
1019 /* Clear overrun flag in 2 Lines communication mode because received is not read */
1020 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
1022 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1025 error :
1026 hspi->State = HAL_SPI_STATE_READY;
1027 __HAL_UNLOCK(hspi);
1028 return errorcode;
1032 * @brief Transmit an amount of data in non-blocking mode with Interrupt.
1033 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1034 * the configuration information for SPI module.
1035 * @param pData: pointer to data buffer
1036 * @param Size: amount of data to be sent
1037 * @retval HAL status
1039 HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1041 HAL_StatusTypeDef errorcode = HAL_OK;
1043 /* Check Direction parameter */
1044 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1046 /* Process Locked */
1047 __HAL_LOCK(hspi);
1049 if((pData == NULL) || (Size == 0))
1051 errorcode = HAL_ERROR;
1052 goto error;
1055 if(hspi->State != HAL_SPI_STATE_READY)
1057 errorcode = HAL_BUSY;
1058 goto error;
1061 /* Set the transaction information */
1062 hspi->State = HAL_SPI_STATE_BUSY_TX;
1063 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1064 hspi->pTxBuffPtr = (uint8_t *)pData;
1065 hspi->TxXferSize = Size;
1066 hspi->TxXferCount = Size;
1068 /* Init field not used in handle to zero */
1069 hspi->pRxBuffPtr = (uint8_t *)NULL;
1070 hspi->RxXferSize = 0U;
1071 hspi->RxXferCount = 0U;
1072 hspi->RxISR = NULL;
1074 /* Set the function for IT treatment */
1075 if(hspi->Init.DataSize > SPI_DATASIZE_8BIT )
1077 hspi->TxISR = SPI_TxISR_16BIT;
1079 else
1081 hspi->TxISR = SPI_TxISR_8BIT;
1084 /* Configure communication direction : 1Line */
1085 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
1087 SPI_1LINE_TX(hspi);
1090 #if (USE_SPI_CRC != 0U)
1091 /* Reset CRC Calculation */
1092 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1094 SPI_RESET_CRC(hspi);
1096 #endif /* USE_SPI_CRC */
1098 if (hspi->Init.Direction == SPI_DIRECTION_2LINES)
1100 /* Enable TXE interrupt */
1101 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE));
1103 else
1105 /* Enable TXE and ERR interrupt */
1106 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
1109 /* Check if the SPI is already enabled */
1110 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1112 /* Enable SPI peripheral */
1113 __HAL_SPI_ENABLE(hspi);
1116 error :
1117 __HAL_UNLOCK(hspi);
1118 return errorcode;
1122 * @brief Receive an amount of data in non-blocking mode with Interrupt.
1123 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1124 * the configuration information for SPI module.
1125 * @param pData: pointer to data buffer
1126 * @param Size: amount of data to be sent
1127 * @retval HAL status
1129 HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1131 HAL_StatusTypeDef errorcode = HAL_OK;
1133 if((hspi->Init.Direction == SPI_DIRECTION_2LINES) && (hspi->Init.Mode == SPI_MODE_MASTER))
1135 hspi->State = HAL_SPI_STATE_BUSY_RX;
1136 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1137 return HAL_SPI_TransmitReceive_IT(hspi, pData, pData, Size);
1140 /* Process Locked */
1141 __HAL_LOCK(hspi);
1143 if(hspi->State != HAL_SPI_STATE_READY)
1145 errorcode = HAL_BUSY;
1146 goto error;
1149 if((pData == NULL) || (Size == 0))
1151 errorcode = HAL_ERROR;
1152 goto error;
1155 /* Set the transaction information */
1156 hspi->State = HAL_SPI_STATE_BUSY_RX;
1157 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1158 hspi->pRxBuffPtr = (uint8_t *)pData;
1159 hspi->RxXferSize = Size;
1160 hspi->RxXferCount = Size;
1162 /* Init field not used in handle to zero */
1163 hspi->pTxBuffPtr = (uint8_t *)NULL;
1164 hspi->TxXferSize = 0U;
1165 hspi->TxXferCount = 0U;
1166 hspi->TxISR = NULL;
1168 /* Set the function for IT treatment */
1169 if(hspi->Init.DataSize > SPI_DATASIZE_8BIT )
1171 hspi->RxISR = SPI_RxISR_16BIT;
1173 else
1175 hspi->RxISR = SPI_RxISR_8BIT;
1178 /* Configure communication direction : 1Line */
1179 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
1181 SPI_1LINE_RX(hspi);
1184 #if (USE_SPI_CRC != 0U)
1185 /* Reset CRC Calculation */
1186 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1188 SPI_RESET_CRC(hspi);
1190 #endif /* USE_SPI_CRC */
1192 /* Enable TXE and ERR interrupt */
1193 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
1195 /* Note : The SPI must be enabled after unlocking current process
1196 to avoid the risk of SPI interrupt handle execution before current
1197 process unlock */
1199 /* Check if the SPI is already enabled */
1200 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1202 /* Enable SPI peripheral */
1203 __HAL_SPI_ENABLE(hspi);
1206 error :
1207 /* Process Unlocked */
1208 __HAL_UNLOCK(hspi);
1209 return errorcode;
1213 * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt.
1214 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1215 * the configuration information for SPI module.
1216 * @param pTxData: pointer to transmission data buffer
1217 * @param pRxData: pointer to reception data buffer
1218 * @param Size: amount of data to be sent and received
1219 * @retval HAL status
1221 HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
1223 uint32_t tmp = 0U, tmp1 = 0U;
1224 HAL_StatusTypeDef errorcode = HAL_OK;
1226 /* Check Direction parameter */
1227 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1229 /* Process locked */
1230 __HAL_LOCK(hspi);
1232 tmp = hspi->State;
1233 tmp1 = hspi->Init.Mode;
1235 if(!((tmp == HAL_SPI_STATE_READY) || \
1236 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1238 errorcode = HAL_BUSY;
1239 goto error;
1242 if((pTxData == NULL ) || (pRxData == NULL ) || (Size == 0))
1244 errorcode = HAL_ERROR;
1245 goto error;
1248 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1249 if(hspi->State == HAL_SPI_STATE_READY)
1251 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1254 /* Set the transaction information */
1255 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1256 hspi->pTxBuffPtr = (uint8_t *)pTxData;
1257 hspi->TxXferSize = Size;
1258 hspi->TxXferCount = Size;
1259 hspi->pRxBuffPtr = (uint8_t *)pRxData;
1260 hspi->RxXferSize = Size;
1261 hspi->RxXferCount = Size;
1263 /* Set the function for IT treatment */
1264 if(hspi->Init.DataSize > SPI_DATASIZE_8BIT )
1266 hspi->RxISR = SPI_2linesRxISR_16BIT;
1267 hspi->TxISR = SPI_2linesTxISR_16BIT;
1269 else
1271 hspi->RxISR = SPI_2linesRxISR_8BIT;
1272 hspi->TxISR = SPI_2linesTxISR_8BIT;
1275 #if (USE_SPI_CRC != 0U)
1276 /* Reset CRC Calculation */
1277 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1279 SPI_RESET_CRC(hspi);
1281 #endif /* USE_SPI_CRC */
1283 /* Enable TXE, RXNE and ERR interrupt */
1284 __HAL_SPI_ENABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
1286 /* Check if the SPI is already enabled */
1287 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1289 /* Enable SPI peripheral */
1290 __HAL_SPI_ENABLE(hspi);
1293 error :
1294 /* Process Unlocked */
1295 __HAL_UNLOCK(hspi);
1296 return errorcode;
1300 * @brief Transmit an amount of data in non-blocking mode with DMA.
1301 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1302 * the configuration information for SPI module.
1303 * @param pData: pointer to data buffer
1304 * @param Size: amount of data to be sent
1305 * @retval HAL status
1307 HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1309 HAL_StatusTypeDef errorcode = HAL_OK;
1311 /* Check Direction parameter */
1312 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE(hspi->Init.Direction));
1314 /* Process Locked */
1315 __HAL_LOCK(hspi);
1317 if(hspi->State != HAL_SPI_STATE_READY)
1319 errorcode = HAL_BUSY;
1320 goto error;
1323 if((pData == NULL) || (Size == 0))
1325 errorcode = HAL_ERROR;
1326 goto error;
1329 /* Set the transaction information */
1330 hspi->State = HAL_SPI_STATE_BUSY_TX;
1331 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1332 hspi->pTxBuffPtr = (uint8_t *)pData;
1333 hspi->TxXferSize = Size;
1334 hspi->TxXferCount = Size;
1336 /* Init field not used in handle to zero */
1337 hspi->pRxBuffPtr = (uint8_t *)NULL;
1338 hspi->TxISR = NULL;
1339 hspi->RxISR = NULL;
1340 hspi->RxXferSize = 0U;
1341 hspi->RxXferCount = 0U;
1343 /* Configure communication direction : 1Line */
1344 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
1346 SPI_1LINE_TX(hspi);
1349 #if (USE_SPI_CRC != 0U)
1350 /* Reset CRC Calculation */
1351 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1353 SPI_RESET_CRC(hspi);
1355 #endif /* USE_SPI_CRC */
1357 /* Set the SPI TxDMA Half transfer complete callback */
1358 hspi->hdmatx->XferHalfCpltCallback = SPI_DMAHalfTransmitCplt;
1360 /* Set the SPI TxDMA transfer complete callback */
1361 hspi->hdmatx->XferCpltCallback = SPI_DMATransmitCplt;
1363 /* Set the DMA error callback */
1364 hspi->hdmatx->XferErrorCallback = SPI_DMAError;
1366 /* Set the DMA AbortCpltCallback */
1367 hspi->hdmatx->XferAbortCallback = NULL;
1369 /* Enable the Tx DMA Stream */
1370 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1372 /* Check if the SPI is already enabled */
1373 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1375 /* Enable SPI peripheral */
1376 __HAL_SPI_ENABLE(hspi);
1379 /* Enable the SPI Error Interrupt Bit */
1380 SET_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1382 /* Enable Tx DMA Request */
1383 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1385 error :
1386 /* Process Unlocked */
1387 __HAL_UNLOCK(hspi);
1388 return errorcode;
1392 * @brief Receive an amount of data in non-blocking mode with DMA.
1393 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1394 * the configuration information for SPI module.
1395 * @param pData: pointer to data buffer
1396 * @note When the CRC feature is enabled the pData Length must be Size + 1.
1397 * @param Size: amount of data to be sent
1398 * @retval HAL status
1400 HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size)
1402 HAL_StatusTypeDef errorcode = HAL_OK;
1404 if((hspi->Init.Direction == SPI_DIRECTION_2LINES)&&(hspi->Init.Mode == SPI_MODE_MASTER))
1406 hspi->State = HAL_SPI_STATE_BUSY_RX;
1407 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1408 return HAL_SPI_TransmitReceive_DMA(hspi, pData, pData, Size);
1411 /* Process Locked */
1412 __HAL_LOCK(hspi);
1414 if(hspi->State != HAL_SPI_STATE_READY)
1416 errorcode = HAL_BUSY;
1417 goto error;
1420 if((pData == NULL) || (Size == 0))
1422 errorcode = HAL_ERROR;
1423 goto error;
1426 /* Set the transaction information */
1427 hspi->State = HAL_SPI_STATE_BUSY_RX;
1428 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1429 hspi->pRxBuffPtr = (uint8_t *)pData;
1430 hspi->RxXferSize = Size;
1431 hspi->RxXferCount = Size;
1433 /*Init field not used in handle to zero */
1434 hspi->RxISR = NULL;
1435 hspi->TxISR = NULL;
1436 hspi->TxXferSize = 0U;
1437 hspi->TxXferCount = 0U;
1439 /* Configure communication direction : 1Line */
1440 if(hspi->Init.Direction == SPI_DIRECTION_1LINE)
1442 SPI_1LINE_RX(hspi);
1445 #if (USE_SPI_CRC != 0U)
1446 /* Reset CRC Calculation */
1447 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1449 SPI_RESET_CRC(hspi);
1451 #endif /* USE_SPI_CRC */
1453 /* Set the SPI RxDMA Half transfer complete callback */
1454 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1456 /* Set the SPI Rx DMA transfer complete callback */
1457 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1459 /* Set the DMA error callback */
1460 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1462 /* Set the DMA AbortCpltCallback */
1463 hspi->hdmarx->XferAbortCallback = NULL;
1465 /* Enable the Rx DMA Stream */
1466 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1468 /* Check if the SPI is already enabled */
1469 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1471 /* Enable SPI peripheral */
1472 __HAL_SPI_ENABLE(hspi);
1475 /* Enable the SPI Error Interrupt Bit */
1476 SET_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1478 /* Enable Rx DMA Request */
1479 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1481 error:
1482 /* Process Unlocked */
1483 __HAL_UNLOCK(hspi);
1484 return errorcode;
1488 * @brief Transmit and Receive an amount of data in non-blocking mode with DMA.
1489 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1490 * the configuration information for SPI module.
1491 * @param pTxData: pointer to transmission data buffer
1492 * @param pRxData: pointer to reception data buffer
1493 * @note When the CRC feature is enabled the pRxData Length must be Size + 1
1494 * @param Size: amount of data to be sent
1495 * @retval HAL status
1497 HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
1499 uint32_t tmp = 0U, tmp1 = 0U;
1500 HAL_StatusTypeDef errorcode = HAL_OK;
1502 /* Check Direction parameter */
1503 assert_param(IS_SPI_DIRECTION_2LINES(hspi->Init.Direction));
1505 /* Process locked */
1506 __HAL_LOCK(hspi);
1508 tmp = hspi->State;
1509 tmp1 = hspi->Init.Mode;
1510 if(!((tmp == HAL_SPI_STATE_READY) ||
1511 ((tmp1 == SPI_MODE_MASTER) && (hspi->Init.Direction == SPI_DIRECTION_2LINES) && (tmp == HAL_SPI_STATE_BUSY_RX))))
1513 errorcode = HAL_BUSY;
1514 goto error;
1517 if((pTxData == NULL ) || (pRxData == NULL ) || (Size == 0))
1519 errorcode = HAL_ERROR;
1520 goto error;
1523 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1524 if(hspi->State == HAL_SPI_STATE_READY)
1526 hspi->State = HAL_SPI_STATE_BUSY_TX_RX;
1529 /* Set the transaction information */
1530 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1531 hspi->pTxBuffPtr = (uint8_t*)pTxData;
1532 hspi->TxXferSize = Size;
1533 hspi->TxXferCount = Size;
1534 hspi->pRxBuffPtr = (uint8_t*)pRxData;
1535 hspi->RxXferSize = Size;
1536 hspi->RxXferCount = Size;
1538 /* Init field not used in handle to zero */
1539 hspi->RxISR = NULL;
1540 hspi->TxISR = NULL;
1542 #if (USE_SPI_CRC != 0U)
1543 /* Reset CRC Calculation */
1544 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
1546 SPI_RESET_CRC(hspi);
1548 #endif /* USE_SPI_CRC */
1550 /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */
1551 if(hspi->State == HAL_SPI_STATE_BUSY_RX)
1553 /* Set the SPI Rx DMA Half transfer complete callback */
1554 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfReceiveCplt;
1555 hspi->hdmarx->XferCpltCallback = SPI_DMAReceiveCplt;
1557 else
1559 /* Set the SPI Tx/Rx DMA Half transfer complete callback */
1560 hspi->hdmarx->XferHalfCpltCallback = SPI_DMAHalfTransmitReceiveCplt;
1561 hspi->hdmarx->XferCpltCallback = SPI_DMATransmitReceiveCplt;
1564 /* Set the DMA error callback */
1565 hspi->hdmarx->XferErrorCallback = SPI_DMAError;
1567 /* Set the DMA AbortCpltCallback */
1568 hspi->hdmarx->XferAbortCallback = NULL;
1570 /* Enable the Rx DMA Stream */
1571 HAL_DMA_Start_IT(hspi->hdmarx, (uint32_t)&hspi->Instance->DR, (uint32_t)hspi->pRxBuffPtr, hspi->RxXferCount);
1573 /* Enable Rx DMA Request */
1574 SET_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
1576 /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing
1577 is performed in DMA reception complete callback */
1578 hspi->hdmatx->XferHalfCpltCallback = NULL;
1579 hspi->hdmatx->XferCpltCallback = NULL;
1580 hspi->hdmatx->XferErrorCallback = NULL;
1581 hspi->hdmatx->XferAbortCallback = NULL;
1583 /* Enable the Tx DMA Stream */
1584 HAL_DMA_Start_IT(hspi->hdmatx, (uint32_t)hspi->pTxBuffPtr, (uint32_t)&hspi->Instance->DR, hspi->TxXferCount);
1586 /* Check if the SPI is already enabled */
1587 if((hspi->Instance->CR1 &SPI_CR1_SPE) != SPI_CR1_SPE)
1589 /* Enable SPI peripheral */
1590 __HAL_SPI_ENABLE(hspi);
1592 /* Enable the SPI Error Interrupt Bit */
1593 SET_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1595 /* Enable Tx DMA Request */
1596 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
1598 error :
1599 /* Process Unlocked */
1600 __HAL_UNLOCK(hspi);
1601 return errorcode;
1605 * @brief Abort ongoing transfer (blocking mode).
1606 * @param hspi SPI handle.
1607 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
1608 * started in Interrupt or DMA mode.
1609 * This procedure performs following operations :
1610 * - Disable SPI Interrupts (depending of transfer direction)
1611 * - Disable the DMA transfer in the peripheral register (if enabled)
1612 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1613 * - Set handle State to READY
1614 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1615 * @note Once transfer is aborted, the __HAL_SPI_CLEAR_OVRFLAG() macro must be called in user application
1616 * before starting new SPI receive process.
1617 * @retval HAL status
1619 HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi)
1621 __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
1623 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
1624 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
1626 hspi->TxISR = SPI_AbortTx_ISR;
1629 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
1631 hspi->RxISR = SPI_AbortRx_ISR;
1634 /* Clear ERRIE interrupts in case of DMA Mode */
1635 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1637 /* Disable the SPI DMA Tx or SPI DMA Rx request if enabled */
1638 if ((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) || (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
1640 /* Abort the SPI DMA Tx channel : use blocking DMA Abort API (no callback) */
1641 if(hspi->hdmatx != NULL)
1643 /* Set the SPI DMA Abort callback :
1644 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
1645 hspi->hdmatx->XferAbortCallback = NULL;
1647 /* Abort DMA Tx Handle linked to SPI Peripheral */
1648 HAL_DMA_Abort(hspi->hdmatx);
1650 /* Disable Tx DMA Request */
1651 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN));
1653 /* Wait until TXE flag is set */
1656 if(count-- == 0U)
1658 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
1659 break;
1662 while((hspi->Instance->SR & SPI_FLAG_TXE) == RESET);
1664 /* Abort the SPI DMA Rx channel : use blocking DMA Abort API (no callback) */
1665 if(hspi->hdmarx != NULL)
1667 /* Set the SPI DMA Abort callback :
1668 will lead to call HAL_SPI_AbortCpltCallback() at end of DMA abort procedure */
1669 hspi->hdmarx->XferAbortCallback = NULL;
1671 /* Abort DMA Rx Handle linked to SPI Peripheral */
1672 HAL_DMA_Abort(hspi->hdmarx);
1674 /* Disable peripheral */
1675 __HAL_SPI_DISABLE(hspi);
1677 /* Disable Rx DMA Request */
1678 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_RXDMAEN));
1682 /* Reset Tx and Rx transfer counters */
1683 hspi->RxXferCount = 0U;
1684 hspi->TxXferCount = 0U;
1686 /* Reset errorCode */
1687 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1689 /* Clear the Error flags in the SR register */
1690 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1691 __HAL_SPI_CLEAR_FREFLAG(hspi);
1693 /* Restore hspi->state to ready */
1694 hspi->State = HAL_SPI_STATE_READY;
1696 return HAL_OK;
1700 * @brief Abort ongoing transfer (Interrupt mode).
1701 * @param hspi SPI handle.
1702 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
1703 * started in Interrupt or DMA mode.
1704 * This procedure performs following operations :
1705 * - Disable SPI Interrupts (depending of transfer direction)
1706 * - Disable the DMA transfer in the peripheral register (if enabled)
1707 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1708 * - Set handle State to READY
1709 * - At abort completion, call user abort complete callback
1710 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1711 * considered as completed only when user abort complete callback is executed (not when exiting function).
1712 * @note Once transfer is aborted, the __HAL_SPI_CLEAR_OVRFLAG() macro must be called in user application
1713 * before starting new SPI receive process.
1714 * @retval HAL status
1716 HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi)
1718 uint32_t abortcplt;
1720 /* Change Rx and Tx Irq Handler to Disable TXEIE, RXNEIE and ERRIE interrupts */
1721 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXEIE))
1723 hspi->TxISR = SPI_AbortTx_ISR;
1726 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXNEIE))
1728 hspi->RxISR = SPI_AbortRx_ISR;
1731 /* Clear ERRIE interrupts in case of DMA Mode */
1732 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_ERRIE);
1734 abortcplt = 1U;
1736 /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialised
1737 before any call to DMA Abort functions */
1738 /* DMA Tx Handle is valid */
1739 if(hspi->hdmatx != NULL)
1741 /* Set DMA Abort Complete callback if UART DMA Tx request if enabled.
1742 Otherwise, set it to NULL */
1743 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
1745 hspi->hdmatx->XferAbortCallback = SPI_DMATxAbortCallback;
1747 else
1749 hspi->hdmatx->XferAbortCallback = NULL;
1752 /* DMA Rx Handle is valid */
1753 if(hspi->hdmarx != NULL)
1755 /* Set DMA Abort Complete callback if UART DMA Rx request if enabled.
1756 Otherwise, set it to NULL */
1757 if(HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
1759 hspi->hdmarx->XferAbortCallback = SPI_DMARxAbortCallback;
1761 else
1763 hspi->hdmarx->XferAbortCallback = NULL;
1767 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
1768 if((HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN)) && (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN)))
1770 /* Abort the SPI DMA Tx channel */
1771 if(hspi->hdmatx != NULL)
1773 /* Abort DMA Tx Handle linked to SPI Peripheral */
1774 if(HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
1776 hspi->hdmatx->XferAbortCallback = NULL;
1778 else
1780 abortcplt = 0U;
1783 /* Abort the SPI DMA Rx channel */
1784 if(hspi->hdmarx != NULL)
1786 /* Abort DMA Rx Handle linked to SPI Peripheral */
1787 if(HAL_DMA_Abort_IT(hspi->hdmarx)!= HAL_OK)
1789 hspi->hdmarx->XferAbortCallback = NULL;
1790 abortcplt = 1U;
1792 else
1794 abortcplt = 0U;
1799 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
1800 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_TXDMAEN))
1802 /* Abort the SPI DMA Tx channel */
1803 if(hspi->hdmatx != NULL)
1805 /* Abort DMA Tx Handle linked to SPI Peripheral */
1806 if(HAL_DMA_Abort_IT(hspi->hdmatx) != HAL_OK)
1808 hspi->hdmatx->XferAbortCallback = NULL;
1810 else
1812 abortcplt = 0U;
1816 /* Disable the SPI DMA Tx or the SPI Rx request if enabled */
1817 if (HAL_IS_BIT_SET(hspi->Instance->CR2, SPI_CR2_RXDMAEN))
1819 /* Abort the SPI DMA Rx channel */
1820 if(hspi->hdmarx != NULL)
1822 /* Abort DMA Rx Handle linked to SPI Peripheral */
1823 if(HAL_DMA_Abort_IT(hspi->hdmarx)!= HAL_OK)
1825 hspi->hdmarx->XferAbortCallback = NULL;
1827 else
1829 abortcplt = 0U;
1834 if(abortcplt == 1U)
1836 /* Reset Tx and Rx transfer counters */
1837 hspi->RxXferCount = 0U;
1838 hspi->TxXferCount = 0U;
1840 /* Reset errorCode */
1841 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
1843 /* Clear the Error flags in the SR register */
1844 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1845 __HAL_SPI_CLEAR_FREFLAG(hspi);
1847 /* Restore hspi->State to Ready */
1848 hspi->State = HAL_SPI_STATE_READY;
1850 /* As no DMA to be aborted, call directly user Abort complete callback */
1851 HAL_SPI_AbortCpltCallback(hspi);
1853 return HAL_OK;
1857 * @brief Pause the DMA Transfer.
1858 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1859 * the configuration information for the specified SPI module.
1860 * @retval HAL status
1862 HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi)
1864 /* Process Locked */
1865 __HAL_LOCK(hspi);
1867 /* Disable the SPI DMA Tx & Rx requests */
1868 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
1870 /* Process Unlocked */
1871 __HAL_UNLOCK(hspi);
1873 return HAL_OK;
1877 * @brief Resume the DMA Transfer.
1878 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1879 * the configuration information for the specified SPI module.
1880 * @retval HAL status
1882 HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi)
1884 /* Process Locked */
1885 __HAL_LOCK(hspi);
1887 /* Enable the SPI DMA Tx & Rx requests */
1888 SET_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
1890 /* Process Unlocked */
1891 __HAL_UNLOCK(hspi);
1893 return HAL_OK;
1897 * @brief Stop the DMA Transfer.
1898 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1899 * the configuration information for the specified SPI module.
1900 * @retval HAL status
1902 HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi)
1904 /* The Lock is not implemented on this API to allow the user application
1905 to call the HAL SPI API under callbacks HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback():
1906 when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
1907 and the correspond call back is executed HAL_SPI_TxCpltCallback() or HAL_SPI_RxCpltCallback() or HAL_SPI_TxRxCpltCallback()
1910 /* Abort the SPI DMA tx Stream */
1911 if(hspi->hdmatx != NULL)
1913 HAL_DMA_Abort(hspi->hdmatx);
1915 /* Abort the SPI DMA rx Stream */
1916 if(hspi->hdmarx != NULL)
1918 HAL_DMA_Abort(hspi->hdmarx);
1921 /* Disable the SPI DMA Tx & Rx requests */
1922 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
1923 hspi->State = HAL_SPI_STATE_READY;
1924 return HAL_OK;
1928 * @brief Handle SPI interrupt request.
1929 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
1930 * the configuration information for the specified SPI module.
1931 * @retval None
1933 void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi)
1935 uint32_t itsource = hspi->Instance->CR2;
1936 uint32_t itflag = hspi->Instance->SR;
1938 /* SPI in mode Receiver ----------------------------------------------------*/
1939 if(((itflag & SPI_FLAG_OVR) == RESET) &&
1940 ((itflag & SPI_FLAG_RXNE) != RESET) && ((itsource & SPI_IT_RXNE) != RESET))
1942 hspi->RxISR(hspi);
1943 return;
1946 /* SPI in mode Transmitter -------------------------------------------------*/
1947 if(((itflag & SPI_FLAG_TXE) != RESET) && ((itsource & SPI_IT_TXE) != RESET))
1949 hspi->TxISR(hspi);
1950 return;
1953 /* SPI in Error Treatment --------------------------------------------------*/
1954 if(((itflag & (SPI_FLAG_MODF | SPI_FLAG_OVR | SPI_FLAG_FRE)) != RESET) && ((itsource & SPI_IT_ERR) != RESET))
1956 /* SPI Overrun error interrupt occurred ----------------------------------*/
1957 if((itflag & SPI_FLAG_OVR) != RESET)
1959 if(hspi->State != HAL_SPI_STATE_BUSY_TX)
1961 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_OVR);
1962 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1964 else
1966 __HAL_SPI_CLEAR_OVRFLAG(hspi);
1967 return;
1971 /* SPI Mode Fault error interrupt occurred -------------------------------*/
1972 if((itflag & SPI_FLAG_MODF) != RESET)
1974 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_MODF);
1975 __HAL_SPI_CLEAR_MODFFLAG(hspi);
1978 /* SPI Frame error interrupt occurred ------------------------------------*/
1979 if((itflag & SPI_FLAG_FRE) != RESET)
1981 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FRE);
1982 __HAL_SPI_CLEAR_FREFLAG(hspi);
1985 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
1987 /* Disable all interrupts */
1988 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE | SPI_IT_TXE | SPI_IT_ERR);
1990 hspi->State = HAL_SPI_STATE_READY;
1991 /* Disable the SPI DMA requests if enabled */
1992 if ((HAL_IS_BIT_SET(itsource, SPI_CR2_TXDMAEN))||(HAL_IS_BIT_SET(itsource, SPI_CR2_RXDMAEN)))
1994 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN));
1996 /* Abort the SPI DMA Rx channel */
1997 if(hspi->hdmarx != NULL)
1999 /* Set the SPI DMA Abort callback :
2000 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2001 hspi->hdmarx->XferAbortCallback = SPI_DMAAbortOnError;
2002 HAL_DMA_Abort_IT(hspi->hdmarx);
2004 /* Abort the SPI DMA Tx channel */
2005 if(hspi->hdmatx != NULL)
2007 /* Set the SPI DMA Abort callback :
2008 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2009 hspi->hdmatx->XferAbortCallback = SPI_DMAAbortOnError;
2010 HAL_DMA_Abort_IT(hspi->hdmatx);
2013 else
2015 /* Call user error callback */
2016 HAL_SPI_ErrorCallback(hspi);
2019 return;
2024 * @brief Tx Transfer completed callback.
2025 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2026 * the configuration information for SPI module.
2027 * @retval None
2029 __weak void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi)
2031 /* Prevent unused argument(s) compilation warning */
2032 UNUSED(hspi);
2033 /* NOTE : This function should not be modified, when the callback is needed,
2034 the HAL_SPI_TxCpltCallback should be implemented in the user file
2039 * @brief Rx Transfer completed callback.
2040 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2041 * the configuration information for SPI module.
2042 * @retval None
2044 __weak void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi)
2046 /* Prevent unused argument(s) compilation warning */
2047 UNUSED(hspi);
2048 /* NOTE : This function should not be modified, when the callback is needed,
2049 the HAL_SPI_RxCpltCallback should be implemented in the user file
2054 * @brief Tx and Rx Transfer completed callback.
2055 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2056 * the configuration information for SPI module.
2057 * @retval None
2059 __weak void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi)
2061 /* Prevent unused argument(s) compilation warning */
2062 UNUSED(hspi);
2063 /* NOTE : This function should not be modified, when the callback is needed,
2064 the HAL_SPI_TxRxCpltCallback should be implemented in the user file
2069 * @brief Tx Half Transfer completed callback.
2070 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2071 * the configuration information for SPI module.
2072 * @retval None
2074 __weak void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2076 /* Prevent unused argument(s) compilation warning */
2077 UNUSED(hspi);
2078 /* NOTE : This function should not be modified, when the callback is needed,
2079 the HAL_SPI_TxHalfCpltCallback should be implemented in the user file
2084 * @brief Rx Half Transfer completed callback.
2085 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2086 * the configuration information for SPI module.
2087 * @retval None
2089 __weak void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2091 /* Prevent unused argument(s) compilation warning */
2092 UNUSED(hspi);
2093 /* NOTE : This function should not be modified, when the callback is needed,
2094 the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file
2099 * @brief Tx and Rx Half Transfer callback.
2100 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2101 * the configuration information for SPI module.
2102 * @retval None
2104 __weak void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi)
2106 /* Prevent unused argument(s) compilation warning */
2107 UNUSED(hspi);
2108 /* NOTE : This function should not be modified, when the callback is needed,
2109 the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file
2114 * @brief SPI error callback.
2115 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2116 * the configuration information for SPI module.
2117 * @retval None
2119 __weak void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi)
2121 /* Prevent unused argument(s) compilation warning */
2122 UNUSED(hspi);
2123 /* NOTE : This function should not be modified, when the callback is needed,
2124 the HAL_SPI_ErrorCallback should be implemented in the user file
2126 /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes
2127 and user can use HAL_SPI_GetError() API to check the latest error occurred
2132 * @brief SPI Abort Complete callback.
2133 * @param hspi SPI handle.
2134 * @retval None
2136 __weak void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi)
2138 /* Prevent unused argument(s) compilation warning */
2139 UNUSED(hspi);
2141 /* NOTE : This function should not be modified, when the callback is needed,
2142 the HAL_SPI_AbortCpltCallback can be implemented in the user file.
2147 * @}
2150 /** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions
2151 * @brief SPI control functions
2153 @verbatim
2154 ===============================================================================
2155 ##### Peripheral State and Errors functions #####
2156 ===============================================================================
2157 [..]
2158 This subsection provides a set of functions allowing to control the SPI.
2159 (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral
2160 (+) HAL_SPI_GetError() check in run-time Errors occurring during communication
2161 @endverbatim
2162 * @{
2166 * @brief Return the SPI handle state.
2167 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2168 * the configuration information for SPI module.
2169 * @retval SPI state
2171 HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi)
2173 /* Return SPI handle state */
2174 return hspi->State;
2178 * @brief Return the SPI error code.
2179 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2180 * the configuration information for SPI module.
2181 * @retval SPI error code in bitmap format
2183 uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi)
2185 /* Return SPI ErrorCode */
2186 return hspi->ErrorCode;
2190 * @}
2194 * @}
2197 /** @addtogroup SPI_Private_Functions
2198 * @brief Private functions
2199 * @{
2203 * @brief DMA SPI transmit process complete callback.
2204 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2205 * the configuration information for the specified DMA module.
2206 * @retval None
2208 static void SPI_DMATransmitCplt(DMA_HandleTypeDef *hdma)
2210 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2211 uint32_t tickstart = 0U;
2213 /* Init tickstart for timeout managment*/
2214 tickstart = HAL_GetTick();
2216 /* DMA Normal Mode */
2217 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U)
2219 /* Disable Tx DMA Request */
2220 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN);
2222 /* Check the end of the transaction */
2223 if(SPI_CheckFlag_BSY(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2225 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2228 /* Clear overrun flag in 2 Lines communication mode because received data is not read */
2229 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
2231 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2234 hspi->TxXferCount = 0U;
2235 hspi->State = HAL_SPI_STATE_READY;
2237 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2239 HAL_SPI_ErrorCallback(hspi);
2240 return;
2243 HAL_SPI_TxCpltCallback(hspi);
2247 * @brief DMA SPI receive process complete callback.
2248 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2249 * the configuration information for the specified DMA module.
2250 * @retval None
2252 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
2254 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2255 #if (USE_SPI_CRC != 0U)
2256 uint32_t tickstart = 0U;
2257 __IO uint16_t tmpreg = 0U;
2259 /* Init tickstart for timeout management*/
2260 tickstart = HAL_GetTick();
2261 #endif /* USE_SPI_CRC */
2263 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U)
2265 #if (USE_SPI_CRC != 0U)
2266 /* CRC handling */
2267 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2269 /* Wait until RXNE flag */
2270 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SPI_FLAG_RXNE, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2272 /* Error on the CRC reception */
2273 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2275 /* Read CRC */
2276 tmpreg = hspi->Instance->DR;
2277 /* To avoid GCC warning */
2278 UNUSED(tmpreg);
2280 #endif /* USE_SPI_CRC */
2282 /* Disable Rx/Tx DMA Request (done by default to handle the case master rx direction 2 lines) */
2283 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2285 /* Check the end of the transaction */
2286 if((hspi->Init.Mode == SPI_MODE_MASTER)&&((hspi->Init.Direction == SPI_DIRECTION_1LINE)||(hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
2288 /* Disable SPI peripheral */
2289 __HAL_SPI_DISABLE(hspi);
2292 hspi->RxXferCount = 0U;
2293 hspi->State = HAL_SPI_STATE_READY;
2295 #if (USE_SPI_CRC != 0U)
2296 /* Check if CRC error occurred */
2297 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2299 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2300 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2302 #endif /* USE_SPI_CRC */
2304 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2306 HAL_SPI_ErrorCallback(hspi);
2307 return;
2310 HAL_SPI_RxCpltCallback(hspi);
2314 * @brief DMA SPI transmit receive process complete callback.
2315 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2316 * the configuration information for the specified DMA module.
2317 * @retval None
2319 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2321 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2322 uint32_t tickstart = 0U;
2323 #if (USE_SPI_CRC != 0U)
2324 __IO int16_t tmpreg = 0U;
2325 #endif /* USE_SPI_CRC */
2326 /* Init tickstart for timeout management*/
2327 tickstart = HAL_GetTick();
2329 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U)
2331 #if (USE_SPI_CRC != 0U)
2332 /* CRC handling */
2333 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2335 /* Wait the CRC data */
2336 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_RXNE, SET, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2338 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2340 /* Read CRC to Flush DR and RXNE flag */
2341 tmpreg = hspi->Instance->DR;
2342 /* To avoid GCC warning */
2343 UNUSED(tmpreg);
2345 #endif /* USE_SPI_CRC */
2346 /* Check the end of the transaction */
2347 if(SPI_CheckFlag_BSY(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
2349 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2352 /* Disable Rx/Tx DMA Request */
2353 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2355 hspi->TxXferCount = 0U;
2356 hspi->RxXferCount = 0U;
2357 hspi->State = HAL_SPI_STATE_READY;
2359 #if (USE_SPI_CRC != 0U)
2360 /* Check if CRC error occurred */
2361 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR))
2363 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
2364 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
2366 #endif /* USE_SPI_CRC */
2368 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
2370 HAL_SPI_ErrorCallback(hspi);
2371 return;
2374 HAL_SPI_TxRxCpltCallback(hspi);
2378 * @brief DMA SPI half transmit process complete callback.
2379 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2380 * the configuration information for the specified DMA module.
2381 * @retval None
2383 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef *hdma)
2385 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2387 HAL_SPI_TxHalfCpltCallback(hspi);
2391 * @brief DMA SPI half receive process complete callback
2392 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2393 * the configuration information for the specified DMA module.
2394 * @retval None
2396 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef *hdma)
2398 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2400 HAL_SPI_RxHalfCpltCallback(hspi);
2404 * @brief DMA SPI half transmit receive process complete callback.
2405 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2406 * the configuration information for the specified DMA module.
2407 * @retval None
2409 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef *hdma)
2411 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2413 HAL_SPI_TxRxHalfCpltCallback(hspi);
2417 * @brief DMA SPI communication error callback.
2418 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
2419 * the configuration information for the specified DMA module.
2420 * @retval None
2422 static void SPI_DMAError(DMA_HandleTypeDef *hdma)
2424 SPI_HandleTypeDef* hspi = (SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2426 /* Stop the disable DMA transfer on SPI side */
2427 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN | SPI_CR2_RXDMAEN);
2429 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_DMA);
2430 hspi->State = HAL_SPI_STATE_READY;
2431 HAL_SPI_ErrorCallback(hspi);
2435 * @brief DMA SPI communication abort callback, when initiated by HAL services on Error
2436 * (To be called at end of DMA Abort procedure following error occurrence).
2437 * @param hdma DMA handle.
2438 * @retval None
2440 static void SPI_DMAAbortOnError(DMA_HandleTypeDef *hdma)
2442 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2443 hspi->RxXferCount = 0U;
2444 hspi->TxXferCount = 0U;
2446 HAL_SPI_ErrorCallback(hspi);
2450 * @brief DMA SPI Tx communication abort callback, when initiated by user
2451 * (To be called at end of DMA Tx Abort procedure following user abort request).
2452 * @note When this callback is executed, User Abort complete call back is called only if no
2453 * Abort still ongoing for Rx DMA Handle.
2454 * @param hdma DMA handle.
2455 * @retval None
2457 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
2459 __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
2460 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2462 hspi->hdmatx->XferAbortCallback = NULL;
2464 /* Disable Tx DMA Request */
2465 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_TXDMAEN );
2467 /* Wait until TXE flag is set */
2470 if(count-- == 0U)
2472 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2473 break;
2476 while((hspi->Instance->SR & SPI_FLAG_TXE) == RESET);
2478 /* Check if an Abort process is still ongoing */
2479 if(hspi->hdmarx != NULL)
2481 if(hspi->hdmarx->XferAbortCallback != NULL)
2483 return;
2487 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2488 hspi->RxXferCount = 0U;
2489 hspi->TxXferCount = 0U;
2491 /* Reset errorCode */
2492 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2494 /* Clear the Error flags in the SR register */
2495 __HAL_SPI_CLEAR_FREFLAG(hspi);
2497 /* Restore hspi->State to Ready */
2498 hspi->State = HAL_SPI_STATE_READY;
2500 /* Call user Abort complete callback */
2501 HAL_SPI_AbortCpltCallback(hspi);
2505 * @brief DMA SPI Rx communication abort callback, when initiated by user
2506 * (To be called at end of DMA Rx Abort procedure following user abort request).
2507 * @note When this callback is executed, User Abort complete call back is called only if no
2508 * Abort still ongoing for Tx DMA Handle.
2509 * @param hdma DMA handle.
2510 * @retval None
2512 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
2514 SPI_HandleTypeDef* hspi = ( SPI_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
2516 /* Disable SPI Peripheral */
2517 __HAL_SPI_DISABLE(hspi);
2519 hspi->hdmarx->XferAbortCallback = NULL;
2521 /* Disable Rx DMA Request */
2522 CLEAR_BIT(hspi->Instance->CR2, SPI_CR2_RXDMAEN);
2524 /* Check if an Abort process is still ongoing */
2525 if(hspi->hdmatx != NULL)
2527 if(hspi->hdmatx->XferAbortCallback != NULL)
2529 return;
2533 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2534 hspi->RxXferCount = 0U;
2535 hspi->TxXferCount = 0U;
2537 /* Reset errorCode */
2538 hspi->ErrorCode = HAL_SPI_ERROR_NONE;
2540 /* Clear the Error flags in the SR register */
2541 __HAL_SPI_CLEAR_OVRFLAG(hspi);
2542 __HAL_SPI_CLEAR_FREFLAG(hspi);
2544 /* Restore hspi->State to Ready */
2545 hspi->State = HAL_SPI_STATE_READY;
2547 /* Call user Abort complete callback */
2548 HAL_SPI_AbortCpltCallback(hspi);
2552 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
2553 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2554 * the configuration information for SPI module.
2555 * @retval None
2557 static void SPI_2linesRxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
2559 /* Receive data in 8bit mode */
2560 *hspi->pRxBuffPtr++ = *((__IO uint8_t *)&hspi->Instance->DR);
2561 hspi->RxXferCount--;
2563 /* check end of the reception */
2564 if(hspi->RxXferCount == 0U)
2566 #if (USE_SPI_CRC != 0U)
2567 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2569 hspi->RxISR = SPI_2linesRxISR_8BITCRC;
2570 return;
2572 #endif /* USE_SPI_CRC */
2574 /* Disable RXNE interrupt */
2575 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
2577 if(hspi->TxXferCount == 0U)
2579 SPI_CloseRxTx_ISR(hspi);
2584 #if (USE_SPI_CRC != 0U)
2586 * @brief Rx 8-bit handler for Transmit and Receive in Interrupt mode.
2587 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2588 * the configuration information for SPI module.
2589 * @retval None
2591 static void SPI_2linesRxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
2593 __IO uint8_t tmpreg = 0U;
2595 /* Read data register to flush CRC */
2596 tmpreg = *((__IO uint8_t *)&hspi->Instance->DR);
2598 /* To avoid GCC warning */
2600 UNUSED(tmpreg);
2602 /* Disable RXNE interrupt */
2603 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
2605 if(hspi->TxXferCount == 0U)
2607 SPI_CloseRxTx_ISR(hspi);
2610 #endif /* USE_SPI_CRC */
2613 * @brief Tx 8-bit handler for Transmit and Receive in Interrupt mode.
2614 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2615 * the configuration information for SPI module.
2616 * @retval None
2618 static void SPI_2linesTxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
2620 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
2621 hspi->TxXferCount--;
2623 /* check the end of the transmission */
2624 if(hspi->TxXferCount == 0U)
2626 #if (USE_SPI_CRC != 0U)
2627 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2629 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2630 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
2631 return;
2633 #endif /* USE_SPI_CRC */
2635 /* Disable TXE interrupt */
2636 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
2638 if(hspi->RxXferCount == 0U)
2640 SPI_CloseRxTx_ISR(hspi);
2646 * @brief Rx 16-bit handler for Transmit and Receive in Interrupt mode.
2647 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2648 * the configuration information for SPI module.
2649 * @retval None
2651 static void SPI_2linesRxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
2653 /* Receive data in 16 Bit mode */
2654 *((uint16_t*)hspi->pRxBuffPtr) = hspi->Instance->DR;
2655 hspi->pRxBuffPtr += sizeof(uint16_t);
2656 hspi->RxXferCount--;
2658 if(hspi->RxXferCount == 0U)
2660 #if (USE_SPI_CRC != 0U)
2661 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2663 hspi->RxISR = SPI_2linesRxISR_16BITCRC;
2664 return;
2666 #endif /* USE_SPI_CRC */
2668 /* Disable RXNE interrupt */
2669 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
2671 if(hspi->TxXferCount == 0U)
2673 SPI_CloseRxTx_ISR(hspi);
2678 #if (USE_SPI_CRC != 0U)
2680 * @brief Manage the CRC 16-bit receive for Transmit and Receive in Interrupt mode.
2681 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2682 * the configuration information for SPI module.
2683 * @retval None
2685 static void SPI_2linesRxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
2687 /* Receive data in 16 Bit mode */
2688 __IO uint16_t tmpreg = 0U;
2690 /* Read data register to flush CRC */
2691 tmpreg = hspi->Instance->DR;
2693 /* To avoid GCC warning */
2694 UNUSED(tmpreg);
2696 /* Disable RXNE interrupt */
2697 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_RXNE);
2699 SPI_CloseRxTx_ISR(hspi);
2701 #endif /* USE_SPI_CRC */
2704 * @brief Tx 16-bit handler for Transmit and Receive in Interrupt mode.
2705 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2706 * the configuration information for SPI module.
2707 * @retval None
2709 static void SPI_2linesTxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
2711 /* Transmit data in 16 Bit mode */
2712 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
2713 hspi->pTxBuffPtr += sizeof(uint16_t);
2714 hspi->TxXferCount--;
2716 /* Enable CRC Transmission */
2717 if(hspi->TxXferCount == 0U)
2719 #if (USE_SPI_CRC != 0U)
2720 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2722 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2723 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
2724 return;
2726 #endif /* USE_SPI_CRC */
2728 /* Disable TXE interrupt */
2729 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_TXE);
2731 if(hspi->RxXferCount == 0U)
2733 SPI_CloseRxTx_ISR(hspi);
2738 #if (USE_SPI_CRC != 0U)
2740 * @brief Manage the CRC 8-bit receive in Interrupt context.
2741 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2742 * the configuration information for SPI module.
2743 * @retval None
2745 static void SPI_RxISR_8BITCRC(struct __SPI_HandleTypeDef *hspi)
2747 __IO uint8_t tmpreg = 0U;
2749 /* Read data register to flush CRC */
2750 tmpreg = *((__IO uint8_t*)&hspi->Instance->DR);
2752 /* To avoid GCC warning */
2753 UNUSED(tmpreg);
2755 SPI_CloseRx_ISR(hspi);
2757 #endif /* USE_SPI_CRC */
2760 * @brief Manage the receive 8-bit in Interrupt context.
2761 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2762 * the configuration information for SPI module.
2763 * @retval None
2765 static void SPI_RxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
2767 *hspi->pRxBuffPtr++ = (*(__IO uint8_t *)&hspi->Instance->DR);
2768 hspi->RxXferCount--;
2770 #if (USE_SPI_CRC != 0U)
2771 /* Enable CRC Transmission */
2772 if((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
2774 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2776 #endif /* USE_SPI_CRC */
2778 if(hspi->RxXferCount == 0U)
2780 #if (USE_SPI_CRC != 0U)
2781 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2783 hspi->RxISR = SPI_RxISR_8BITCRC;
2784 return;
2786 #endif /* USE_SPI_CRC */
2787 SPI_CloseRx_ISR(hspi);
2791 #if (USE_SPI_CRC != 0U)
2793 * @brief Manage the CRC 16-bit receive in Interrupt context.
2794 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2795 * the configuration information for SPI module.
2796 * @retval None
2798 static void SPI_RxISR_16BITCRC(struct __SPI_HandleTypeDef *hspi)
2800 __IO uint16_t tmpreg = 0U;
2802 /* Read data register to flush CRC */
2803 tmpreg = hspi->Instance->DR;
2805 /* To avoid GCC warning */
2806 UNUSED(tmpreg);
2808 /* Disable RXNE and ERR interrupt */
2809 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
2811 SPI_CloseRx_ISR(hspi);
2813 #endif /* USE_SPI_CRC */
2816 * @brief Manage the 16-bit receive in Interrupt context.
2817 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2818 * the configuration information for SPI module.
2819 * @retval None
2821 static void SPI_RxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
2823 *((uint16_t *)hspi->pRxBuffPtr) = hspi->Instance->DR;
2824 hspi->pRxBuffPtr += sizeof(uint16_t);
2825 hspi->RxXferCount--;
2827 #if (USE_SPI_CRC != 0U)
2828 /* Enable CRC Transmission */
2829 if((hspi->RxXferCount == 1U) && (hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE))
2831 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2833 #endif /* USE_SPI_CRC */
2835 if(hspi->RxXferCount == 0U)
2837 #if (USE_SPI_CRC != 0U)
2838 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2840 hspi->RxISR = SPI_RxISR_16BITCRC;
2841 return;
2843 #endif /* USE_SPI_CRC */
2844 SPI_CloseRx_ISR(hspi);
2849 * @brief Handle the data 8-bit transmit in Interrupt mode.
2850 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2851 * the configuration information for SPI module.
2852 * @retval None
2854 static void SPI_TxISR_8BIT(struct __SPI_HandleTypeDef *hspi)
2856 *(__IO uint8_t *)&hspi->Instance->DR = (*hspi->pTxBuffPtr++);
2857 hspi->TxXferCount--;
2859 if(hspi->TxXferCount == 0U)
2861 #if (USE_SPI_CRC != 0U)
2862 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2864 /* Enable CRC Transmission */
2865 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2867 #endif /* USE_SPI_CRC */
2868 SPI_CloseTx_ISR(hspi);
2873 * @brief Handle the data 16-bit transmit in Interrupt mode.
2874 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2875 * the configuration information for SPI module.
2876 * @retval None
2878 static void SPI_TxISR_16BIT(struct __SPI_HandleTypeDef *hspi)
2880 /* Transmit data in 16 Bit mode */
2881 hspi->Instance->DR = *((uint16_t *)hspi->pTxBuffPtr);
2882 hspi->pTxBuffPtr += sizeof(uint16_t);
2883 hspi->TxXferCount--;
2885 if(hspi->TxXferCount == 0U)
2887 #if (USE_SPI_CRC != 0U)
2888 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2890 /* Enable CRC Transmission */
2891 SET_BIT(hspi->Instance->CR1, SPI_CR1_CRCNEXT);
2893 #endif /* USE_SPI_CRC */
2894 SPI_CloseTx_ISR(hspi);
2899 * @brief Handle SPI Communication Timeout.
2900 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2901 * the configuration information for SPI module.
2902 * @param Flag: SPI flag to check
2903 * @param State: flag state to check
2904 * @param Timeout: Timeout duration
2905 * @param Tickstart: tick start value
2906 * @retval HAL status
2908 static HAL_StatusTypeDef SPI_WaitFlagStateUntilTimeout(SPI_HandleTypeDef *hspi, uint32_t Flag, uint32_t State, uint32_t Timeout, uint32_t Tickstart)
2910 while((((hspi->Instance->SR & Flag) == (Flag)) ? SET : RESET) != State)
2912 if(Timeout != HAL_MAX_DELAY)
2914 if((Timeout == 0U) || ((HAL_GetTick()-Tickstart) >= Timeout))
2916 /* Disable the SPI and reset the CRC: the CRC value should be cleared
2917 on both master and slave sides in order to resynchronize the master
2918 and slave for their respective CRC calculation */
2920 /* Disable TXE, RXNE and ERR interrupts for the interrupt process */
2921 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_RXNE | SPI_IT_ERR));
2923 if((hspi->Init.Mode == SPI_MODE_MASTER)&&((hspi->Init.Direction == SPI_DIRECTION_1LINE)||(hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
2925 /* Disable SPI peripheral */
2926 __HAL_SPI_DISABLE(hspi);
2929 /* Reset CRC Calculation */
2930 if(hspi->Init.CRCCalculation == SPI_CRCCALCULATION_ENABLE)
2932 SPI_RESET_CRC(hspi);
2935 hspi->State= HAL_SPI_STATE_READY;
2937 /* Process Unlocked */
2938 __HAL_UNLOCK(hspi);
2940 return HAL_TIMEOUT;
2945 return HAL_OK;
2948 * @brief Handle to check BSY flag before start a new transaction.
2949 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2950 * the configuration information for SPI module.
2951 * @param Timeout: Timeout duration
2952 * @param Tickstart: tick start value
2953 * @retval HAL status
2955 static HAL_StatusTypeDef SPI_CheckFlag_BSY(SPI_HandleTypeDef *hspi, uint32_t Timeout, uint32_t Tickstart)
2957 /* Control the BSY flag */
2958 if(SPI_WaitFlagStateUntilTimeout(hspi, SPI_FLAG_BSY, RESET, Timeout, Tickstart) != HAL_OK)
2960 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2961 return HAL_TIMEOUT;
2963 return HAL_OK;
2967 * @brief Handle the end of the RXTX transaction.
2968 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2969 * the configuration information for SPI module.
2970 * @retval None
2972 static void SPI_CloseRxTx_ISR(SPI_HandleTypeDef *hspi)
2974 uint32_t tickstart = 0U;
2975 __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
2976 /* Init tickstart for timeout managment*/
2977 tickstart = HAL_GetTick();
2979 /* Disable ERR interrupt */
2980 __HAL_SPI_DISABLE_IT(hspi, SPI_IT_ERR);
2982 /* Wait until TXE flag is set */
2985 if(count-- == 0U)
2987 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2988 break;
2991 while((hspi->Instance->SR & SPI_FLAG_TXE) == RESET);
2993 /* Check the end of the transaction */
2994 if(SPI_CheckFlag_BSY(hspi, SPI_DEFAULT_TIMEOUT, tickstart)!=HAL_OK)
2996 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
2999 /* Clear overrun flag in 2 Lines communication mode because received is not read */
3000 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
3002 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3005 #if (USE_SPI_CRC != 0U)
3006 /* Check if CRC error occurred */
3007 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3009 hspi->State = HAL_SPI_STATE_READY;
3010 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3011 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3012 HAL_SPI_ErrorCallback(hspi);
3014 else
3016 #endif /* USE_SPI_CRC */
3017 if(hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3019 if(hspi->State == HAL_SPI_STATE_BUSY_RX)
3021 hspi->State = HAL_SPI_STATE_READY;
3022 HAL_SPI_RxCpltCallback(hspi);
3024 else
3026 hspi->State = HAL_SPI_STATE_READY;
3027 HAL_SPI_TxRxCpltCallback(hspi);
3030 else
3032 hspi->State = HAL_SPI_STATE_READY;
3033 HAL_SPI_ErrorCallback(hspi);
3035 #if (USE_SPI_CRC != 0U)
3037 #endif /* USE_SPI_CRC */
3041 * @brief Handle the end of the RX transaction.
3042 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3043 * the configuration information for SPI module.
3044 * @retval None
3046 static void SPI_CloseRx_ISR(SPI_HandleTypeDef *hspi)
3048 /* Disable RXNE and ERR interrupt */
3049 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_RXNE | SPI_IT_ERR));
3051 /* Check the end of the transaction */
3052 if((hspi->Init.Mode == SPI_MODE_MASTER)&&((hspi->Init.Direction == SPI_DIRECTION_1LINE)||(hspi->Init.Direction == SPI_DIRECTION_2LINES_RXONLY)))
3054 /* Disable SPI peripheral */
3055 __HAL_SPI_DISABLE(hspi);
3058 /* Clear overrun flag in 2 Lines communication mode because received is not read */
3059 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
3061 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3063 hspi->State = HAL_SPI_STATE_READY;
3065 #if (USE_SPI_CRC != 0U)
3066 /* Check if CRC error occurred */
3067 if(__HAL_SPI_GET_FLAG(hspi, SPI_FLAG_CRCERR) != RESET)
3069 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_CRC);
3070 __HAL_SPI_CLEAR_CRCERRFLAG(hspi);
3071 HAL_SPI_ErrorCallback(hspi);
3073 else
3075 #endif /* USE_SPI_CRC */
3076 if(hspi->ErrorCode == HAL_SPI_ERROR_NONE)
3078 HAL_SPI_RxCpltCallback(hspi);
3080 else
3082 HAL_SPI_ErrorCallback(hspi);
3084 #if (USE_SPI_CRC != 0U)
3086 #endif /* USE_SPI_CRC */
3090 * @brief Handle the end of the TX transaction.
3091 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3092 * the configuration information for SPI module.
3093 * @retval None
3095 static void SPI_CloseTx_ISR(SPI_HandleTypeDef *hspi)
3097 uint32_t tickstart = 0U;
3098 __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
3100 /* Init tickstart for timeout management*/
3101 tickstart = HAL_GetTick();
3103 /* Wait until TXE flag is set */
3106 if(count-- == 0U)
3108 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3109 break;
3112 while((hspi->Instance->SR & SPI_FLAG_TXE) == RESET);
3114 /* Disable TXE and ERR interrupt */
3115 __HAL_SPI_DISABLE_IT(hspi, (SPI_IT_TXE | SPI_IT_ERR));
3117 /* Check Busy flag */
3118 if(SPI_CheckFlag_BSY(hspi, SPI_DEFAULT_TIMEOUT, tickstart) != HAL_OK)
3120 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3123 /* Clear overrun flag in 2 Lines communication mode because received is not read */
3124 if(hspi->Init.Direction == SPI_DIRECTION_2LINES)
3126 __HAL_SPI_CLEAR_OVRFLAG(hspi);
3129 hspi->State = HAL_SPI_STATE_READY;
3130 if(hspi->ErrorCode != HAL_SPI_ERROR_NONE)
3132 HAL_SPI_ErrorCallback(hspi);
3134 else
3136 HAL_SPI_TxCpltCallback(hspi);
3141 * @}
3145 * @brief Handle abort a Tx or Rx transaction.
3146 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3147 * the configuration information for SPI module.
3148 * @retval None
3150 static void SPI_AbortRx_ISR(SPI_HandleTypeDef *hspi)
3152 __IO uint32_t tmpreg = 0U;
3153 __IO uint32_t count = SPI_DEFAULT_TIMEOUT * (SystemCoreClock / 24U / 1000U);
3155 /* Wait until TXE flag is set */
3158 if(count-- == 0U)
3160 SET_BIT(hspi->ErrorCode, HAL_SPI_ERROR_FLAG);
3161 break;
3164 while((hspi->Instance->SR & SPI_FLAG_TXE) == RESET);
3166 /* Disable SPI Peripheral */
3167 __HAL_SPI_DISABLE(hspi);
3169 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3170 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3172 /* Flush DR Register */
3173 tmpreg = (*(__IO uint32_t *)&hspi->Instance->DR);
3175 /* To avoid GCC warning */
3176 UNUSED(tmpreg);
3180 * @brief Handle abort a Tx or Rx transaction.
3181 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3182 * the configuration information for SPI module.
3183 * @retval None
3185 static void SPI_AbortTx_ISR(SPI_HandleTypeDef *hspi)
3187 /* Disable TXEIE, RXNEIE and ERRIE(mode fault event, overrun error, TI frame error) interrupts */
3188 CLEAR_BIT(hspi->Instance->CR2, (SPI_CR2_TXEIE | SPI_CR2_RXNEIE | SPI_CR2_ERRIE));
3190 /* Disable SPI Peripheral */
3191 __HAL_SPI_DISABLE(hspi);
3194 * @}
3196 #endif /* HAL_SPI_MODULE_ENABLED */
3199 * @}
3203 * @}
3206 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/