2 ******************************************************************************
3 * @file stm32h7xx_hal_spi.c
4 * @author MCD Application Team
5 * @brief SPI HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Serial Peripheral Interface (SPI) peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral Control functions
11 * + Peripheral State functions
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
18 The SPI HAL driver can be used as follows:
20 (#) Declare a SPI_HandleTypeDef handle structure, for example:
21 SPI_HandleTypeDef hspi;
23 (#)Initialize the SPI low level resources by implementing the HAL_SPI_MspInit() API:
24 (##) Enable the SPIx interface clock
25 (##) SPI pins configuration
26 (+++) Enable the clock for the SPI GPIOs
27 (+++) Configure these SPI pins as alternate function push-pull
28 (##) NVIC configuration if you need to use interrupt process or DMA process
29 (+++) Configure the SPIx interrupt priority
30 (+++) Enable the NVIC SPI IRQ handle
31 (##) DMA Configuration if you need to use DMA process
32 (+++) Declare a DMA_HandleTypeDef handle structure for the transmit or receive Stream/Channel
33 (+++) Enable the DMAx clock
34 (+++) Configure the DMA handle parameters
35 (+++) Configure the DMA Tx or Rx Stream/Channel
36 (+++) Associate the initialized hdma_tx handle to the hspi DMA Tx or Rx handle
37 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx or Rx Stream/Channel
39 (#) Program the Mode, BidirectionalMode , Data size, Baudrate Prescaler, NSS
40 management, Clock polarity and phase, FirstBit and CRC configuration in the hspi Init structure.
42 (#) Initialize the SPI registers by calling the HAL_SPI_Init() API:
43 (++) This API configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
44 by calling the customized HAL_SPI_MspInit() API.
46 Callback registration:
48 (#) The compilation flag USE_HAL_SPI_REGISTER_CALLBACKS when set to 1UL
49 allows the user to configure dynamically the driver callbacks.
50 Use Functions HAL_SPI_RegisterCallback() to register an interrupt callback.
52 Function HAL_SPI_RegisterCallback() allows to register following callbacks:
53 (+) TxCpltCallback : SPI Tx Completed callback
54 (+) RxCpltCallback : SPI Rx Completed callback
55 (+) TxRxCpltCallback : SPI TxRx Completed callback
56 (+) TxHalfCpltCallback : SPI Tx Half Completed callback
57 (+) RxHalfCpltCallback : SPI Rx Half Completed callback
58 (+) TxRxHalfCpltCallback : SPI TxRx Half Completed callback
59 (+) ErrorCallback : SPI Error callback
60 (+) AbortCpltCallback : SPI Abort callback
61 (+) MspInitCallback : SPI Msp Init callback
62 (+) MspDeInitCallback : SPI Msp DeInit callback
63 This function takes as parameters the HAL peripheral handle, the Callback ID
64 and a pointer to the user callback function.
67 (#) Use function HAL_SPI_UnRegisterCallback to reset a callback to the default
69 HAL_SPI_UnRegisterCallback takes as parameters the HAL peripheral handle,
71 This function allows to reset following callbacks:
72 (+) TxCpltCallback : SPI Tx Completed callback
73 (+) RxCpltCallback : SPI Rx Completed callback
74 (+) TxRxCpltCallback : SPI TxRx Completed callback
75 (+) TxHalfCpltCallback : SPI Tx Half Completed callback
76 (+) RxHalfCpltCallback : SPI Rx Half Completed callback
77 (+) TxRxHalfCpltCallback : SPI TxRx Half Completed callback
78 (+) ErrorCallback : SPI Error callback
79 (+) AbortCpltCallback : SPI Abort callback
80 (+) MspInitCallback : SPI Msp Init callback
81 (+) MspDeInitCallback : SPI Msp DeInit callback
83 By default, after the HAL_SPI_Init() and when the state is HAL_SPI_STATE_RESET
84 all callbacks are set to the corresponding weak functions:
85 examples HAL_SPI_MasterTxCpltCallback(), HAL_SPI_MasterRxCpltCallback().
86 Exception done for MspInit and MspDeInit functions that are
87 reset to the legacy weak functions in the HAL_SPI_Init()/ HAL_SPI_DeInit() only when
88 these callbacks are null (not registered beforehand).
89 If MspInit or MspDeInit are not null, the HAL_SPI_Init()/ HAL_SPI_DeInit()
90 keep and use the user MspInit/MspDeInit callbacks (registered beforehand) whatever the state.
92 Callbacks can be registered/unregistered in HAL_SPI_STATE_READY state only.
93 Exception done MspInit/MspDeInit functions that can be registered/unregistered
94 in HAL_SPI_STATE_READY or HAL_SPI_STATE_RESET state,
95 thus registered (user) MspInit/DeInit callbacks can be used during the Init/DeInit.
96 Then, the user first registers the MspInit/MspDeInit user callbacks
97 using HAL_SPI_RegisterCallback() before calling HAL_SPI_DeInit()
98 or HAL_SPI_Init() function.
100 When The compilation define USE_HAL_PPP_REGISTER_CALLBACKS is set to 0 or
101 not defined, the callback registering feature is not available
102 and weak (surcharged) callbacks are used.
106 Circular mode restriction:
107 (+) The DMA circular mode cannot be used when the SPI is configured in these modes:
108 (++) Master 2Lines RxOnly
110 (+) The CRC feature is not managed when the DMA circular mode is enabled
111 (+) The functions HAL_SPI_DMAPause()/ HAL_SPI_DMAResume() are not supported. Return always
112 HAL_ERROR with ErrorCode set to HAL_SPI_ERROR_NOT_SUPPORTED.
113 Those functions are maintained for backward compatibility reasons.
116 ******************************************************************************
119 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
120 * All rights reserved.</center></h2>
122 * This software component is licensed by ST under BSD 3-Clause license,
123 * the "License"; You may not use this file except in compliance with the
124 * License. You may obtain a copy of the License at:
125 * opensource.org/licenses/BSD-3-Clause
127 ******************************************************************************
130 /* Includes ------------------------------------------------------------------*/
131 #include "stm32h7xx_hal.h"
133 /** @addtogroup STM32H7xx_HAL_Driver
137 /** @defgroup SPI SPI
138 * @brief SPI HAL module driver
141 #ifdef HAL_SPI_MODULE_ENABLED
143 /* Private typedef -----------------------------------------------------------*/
144 /* Private defines -----------------------------------------------------------*/
145 /** @defgroup SPI_Private_Constants SPI Private Constants
148 #define SPI_DEFAULT_TIMEOUT 100UL
153 /* Private macros ------------------------------------------------------------*/
154 /* Private variables ---------------------------------------------------------*/
155 /* Private function prototypes -----------------------------------------------*/
156 /** @defgroup SPI_Private_Functions SPI Private Functions
159 static void SPI_DMATransmitCplt(DMA_HandleTypeDef
*hdma
);
160 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
);
161 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef
*hdma
);
162 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef
*hdma
);
163 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef
*hdma
);
164 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef
*hdma
);
165 static void SPI_DMAError(DMA_HandleTypeDef
*hdma
);
166 static void SPI_DMAAbortOnError(DMA_HandleTypeDef
*hdma
);
167 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
);
168 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
);
169 static HAL_StatusTypeDef
SPI_WaitOnFlagUntilTimeout(SPI_HandleTypeDef
*hspi
, uint32_t Flag
, FlagStatus FlagStatus
,
170 uint32_t Timeout
, uint32_t Tickstart
);
171 static void SPI_TxISR_8BIT(SPI_HandleTypeDef
*hspi
);
172 static void SPI_TxISR_16BIT(SPI_HandleTypeDef
*hspi
);
173 static void SPI_TxISR_32BIT(SPI_HandleTypeDef
*hspi
);
174 static void SPI_RxISR_8BIT(SPI_HandleTypeDef
*hspi
);
175 static void SPI_RxISR_16BIT(SPI_HandleTypeDef
*hspi
);
176 static void SPI_RxISR_32BIT(SPI_HandleTypeDef
*hspi
);
177 static void SPI_AbortTransfer(SPI_HandleTypeDef
*hspi
);
178 static void SPI_CloseTransfer(SPI_HandleTypeDef
*hspi
);
179 static uint32_t SPI_GetPacketSize(SPI_HandleTypeDef
*hspi
);
186 /* Exported functions --------------------------------------------------------*/
187 /** @defgroup SPI_Exported_Functions SPI Exported Functions
191 /** @defgroup SPI_Exported_Functions_Group1 Initialization and de-initialization functions
192 * @brief Initialization and Configuration functions
195 ===============================================================================
196 ##### Initialization and de-initialization functions #####
197 ===============================================================================
198 [..] This subsection provides a set of functions allowing to initialize and
199 de-initialize the SPIx peripheral:
201 (+) User must implement HAL_SPI_MspInit() function in which he configures
202 all related peripherals resources (CLOCK, GPIO, DMA, IT and NVIC ).
204 (+) Call the function HAL_SPI_Init() to configure the selected device with
205 the selected configuration:
209 (++) Clock Polarity and Phase
211 (++) BaudRate Prescaler
215 (++) CRC Polynomial if CRC enabled
216 (++) CRC Length, used only with Data8 and Data16
217 (++) FIFO reception threshold
218 (++) FIFO transmission threshold
220 (+) Call the function HAL_SPI_DeInit() to restore the default configuration
221 of the selected SPIx peripheral.
228 * @brief Initialize the SPI according to the specified parameters
229 * in the SPI_InitTypeDef and initialize the associated handle.
230 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
231 * the configuration information for SPI module.
234 HAL_StatusTypeDef
HAL_SPI_Init(SPI_HandleTypeDef
*hspi
)
236 uint32_t crc_length
= 0UL;
237 uint32_t packet_length
;
239 /* Check the SPI handle allocation */
245 /* Check the parameters */
246 assert_param(IS_SPI_ALL_INSTANCE(hspi
->Instance
));
247 assert_param(IS_SPI_MODE(hspi
->Init
.Mode
));
248 assert_param(IS_SPI_DIRECTION(hspi
->Init
.Direction
));
249 assert_param(IS_SPI_DATASIZE(hspi
->Init
.DataSize
));
250 assert_param(IS_SPI_FIFOTHRESHOLD(hspi
->Init
.FifoThreshold
));
251 assert_param(IS_SPI_NSS(hspi
->Init
.NSS
));
252 assert_param(IS_SPI_NSSP(hspi
->Init
.NSSPMode
));
253 assert_param(IS_SPI_BAUDRATE_PRESCALER(hspi
->Init
.BaudRatePrescaler
));
254 assert_param(IS_SPI_FIRST_BIT(hspi
->Init
.FirstBit
));
255 assert_param(IS_SPI_TIMODE(hspi
->Init
.TIMode
));
256 if (hspi
->Init
.TIMode
== SPI_TIMODE_DISABLE
)
258 assert_param(IS_SPI_CPOL(hspi
->Init
.CLKPolarity
));
259 assert_param(IS_SPI_CPHA(hspi
->Init
.CLKPhase
));
261 #if (USE_SPI_CRC != 0UL)
262 assert_param(IS_SPI_CRC_CALCULATION(hspi
->Init
.CRCCalculation
));
263 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_ENABLE
)
265 assert_param(IS_SPI_CRC_POLYNOMIAL(hspi
->Init
.CRCPolynomial
));
266 assert_param(IS_SPI_CRC_LENGTH(hspi
->Init
.CRCLength
));
267 assert_param(IS_SPI_CRC_INITIALIZATION_PATTERN(hspi
->Init
.TxCRCInitializationPattern
));
268 assert_param(IS_SPI_CRC_INITIALIZATION_PATTERN(hspi
->Init
.RxCRCInitializationPattern
));
271 hspi
->Init
.CRCCalculation
= SPI_CRCCALCULATION_DISABLE
;
272 #endif /* USE_SPI_CRC */
274 /* Verify that the SPI instance supports Data Size higher than 16bits */
275 if ((!IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
))
280 /* Verify that the SPI instance supports requested data packing */
281 packet_length
= SPI_GetPacketSize(hspi
);
282 if (((!IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (packet_length
> SPI_LOWEND_FIFO_SIZE
)) ||
283 ((IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (packet_length
> SPI_HIGHEND_FIFO_SIZE
)))
288 #if (USE_SPI_CRC != 0UL)
289 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_ENABLE
)
291 /* Verify that the SPI instance supports CRC Length higher than 16bits */
292 if ((!IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (hspi
->Init
.CRCLength
> SPI_CRC_LENGTH_16BIT
))
297 /* Align the CRC Length on the data size */
298 if (hspi
->Init
.CRCLength
== SPI_CRC_LENGTH_DATASIZE
)
300 crc_length
= (hspi
->Init
.DataSize
>> SPI_CFG1_DSIZE_Pos
) << SPI_CFG1_CRCSIZE_Pos
;
304 crc_length
= hspi
->Init
.CRCLength
;
307 /* Verify that the CRC Length is higher than DataSize */
308 if ((hspi
->Init
.DataSize
>> SPI_CFG1_DSIZE_Pos
) > (crc_length
>> SPI_CFG1_CRCSIZE_Pos
))
313 #endif /* USE_SPI_CRC */
315 if (hspi
->State
== HAL_SPI_STATE_RESET
)
317 /* Allocate lock resource and initialize it */
318 hspi
->Lock
= HAL_UNLOCKED
;
320 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
321 /* Init the SPI Callback settings */
322 hspi
->TxCpltCallback
= HAL_SPI_TxCpltCallback
; /* Legacy weak TxCpltCallback */
323 hspi
->RxCpltCallback
= HAL_SPI_RxCpltCallback
; /* Legacy weak RxCpltCallback */
324 hspi
->TxRxCpltCallback
= HAL_SPI_TxRxCpltCallback
; /* Legacy weak TxRxCpltCallback */
325 hspi
->TxHalfCpltCallback
= HAL_SPI_TxHalfCpltCallback
; /* Legacy weak TxHalfCpltCallback */
326 hspi
->RxHalfCpltCallback
= HAL_SPI_RxHalfCpltCallback
; /* Legacy weak RxHalfCpltCallback */
327 hspi
->TxRxHalfCpltCallback
= HAL_SPI_TxRxHalfCpltCallback
; /* Legacy weak TxRxHalfCpltCallback */
328 hspi
->ErrorCallback
= HAL_SPI_ErrorCallback
; /* Legacy weak ErrorCallback */
329 hspi
->AbortCpltCallback
= HAL_SPI_AbortCpltCallback
; /* Legacy weak AbortCpltCallback */
331 if (hspi
->MspInitCallback
== NULL
)
333 hspi
->MspInitCallback
= HAL_SPI_MspInit
; /* Legacy weak MspInit */
336 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
337 hspi
->MspInitCallback(hspi
);
339 /* Init the low level hardware : GPIO, CLOCK, NVIC... */
340 HAL_SPI_MspInit(hspi
);
341 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
344 hspi
->State
= HAL_SPI_STATE_BUSY
;
346 /* Disable the selected SPI peripheral */
347 __HAL_SPI_DISABLE(hspi
);
349 /*----------------------- SPIx CR1 & CR2 Configuration ---------------------*/
350 /* Configure : SPI Mode, Communication Mode, Clock polarity and phase, NSS management,
351 Communication speed, First bit, CRC calculation state, CRC Length */
353 if ((hspi
->Init
.NSS
== SPI_NSS_SOFT
) && (hspi
->Init
.Mode
== SPI_MODE_MASTER
) && (hspi
->Init
.NSSPolarity
== SPI_NSS_POLARITY_LOW
))
355 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_SSI
);
358 /* SPIx CFG1 Configuration */
359 WRITE_REG(hspi
->Instance
->CFG1
, (hspi
->Init
.BaudRatePrescaler
| hspi
->Init
.CRCCalculation
| crc_length
|
360 hspi
->Init
.FifoThreshold
| hspi
->Init
.DataSize
));
362 /* SPIx CFG2 Configuration */
363 WRITE_REG(hspi
->Instance
->CFG2
, (hspi
->Init
.NSSPMode
| hspi
->Init
.TIMode
| hspi
->Init
.NSSPolarity
|
364 hspi
->Init
.NSS
| hspi
->Init
.CLKPolarity
| hspi
->Init
.CLKPhase
|
365 hspi
->Init
.FirstBit
| hspi
->Init
.Mode
| hspi
->Init
.MasterInterDataIdleness
|
366 hspi
->Init
.Direction
| hspi
->Init
.MasterSSIdleness
| hspi
->Init
.IOSwap
));
368 #if (USE_SPI_CRC != 0UL)
369 /*---------------------------- SPIx CRCPOLY Configuration ------------------*/
370 /* Configure : CRC Polynomial */
371 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_ENABLE
)
373 /* Initialize TXCRC Pattern Initial Value */
374 if (hspi
->Init
.TxCRCInitializationPattern
== SPI_CRC_INITIALIZATION_ALL_ONE_PATTERN
)
376 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_TCRCINI
);
380 CLEAR_BIT(hspi
->Instance
->CR1
, SPI_CR1_TCRCINI
);
383 /* Initialize RXCRC Pattern Initial Value */
384 if (hspi
->Init
.RxCRCInitializationPattern
== SPI_CRC_INITIALIZATION_ALL_ONE_PATTERN
)
386 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_RCRCINI
);
390 CLEAR_BIT(hspi
->Instance
->CR1
, SPI_CR1_RCRCINI
);
393 /* Enable 33/17 bits CRC computation */
394 if (((!IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (crc_length
== SPI_CRC_LENGTH_16BIT
)) ||
395 ((IS_SPI_HIGHEND_INSTANCE(hspi
->Instance
)) && (crc_length
== SPI_CRC_LENGTH_32BIT
)))
397 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CRC33_17
);
401 CLEAR_BIT(hspi
->Instance
->CR1
, SPI_CR1_CRC33_17
);
404 /* Write CRC polynomial in SPI Register */
405 WRITE_REG(hspi
->Instance
->CRCPOLY
, hspi
->Init
.CRCPolynomial
);
407 #endif /* USE_SPI_CRC */
409 /* Insure that Underrun configuration is managed only by Salve */
410 if (hspi
->Init
.Mode
== SPI_MODE_SLAVE
)
412 /* Set Default Underrun configuration */
413 #if (USE_SPI_CRC != 0UL)
414 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_DISABLE
)
417 MODIFY_REG(hspi
->Instance
->CFG1
, SPI_CFG1_UDRDET
, SPI_CFG1_UDRDET_0
);
419 MODIFY_REG(hspi
->Instance
->CFG1
, SPI_CFG1_UDRCFG
, SPI_CFG1_UDRCFG_1
);
422 #if defined(SPI_I2SCFGR_I2SMOD)
423 /* Activate the SPI mode (Make sure that I2SMOD bit in I2SCFGR register is reset) */
424 CLEAR_BIT(hspi
->Instance
->I2SCFGR
, SPI_I2SCFGR_I2SMOD
);
425 #endif /* SPI_I2SCFGR_I2SMOD */
427 /* Insure that AFCNTR is managed only by Master */
428 if ((hspi
->Init
.Mode
& SPI_MODE_MASTER
) == SPI_MODE_MASTER
)
430 /* Alternate function GPIOs control */
431 MODIFY_REG(hspi
->Instance
->CFG2
, SPI_CFG2_AFCNTR
, (hspi
->Init
.MasterKeepIOState
));
434 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
435 hspi
->State
= HAL_SPI_STATE_READY
;
441 * @brief De-Initialize the SPI peripheral.
442 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
443 * the configuration information for SPI module.
446 HAL_StatusTypeDef
HAL_SPI_DeInit(SPI_HandleTypeDef
*hspi
)
448 /* Check the SPI handle allocation */
454 /* Check SPI Instance parameter */
455 assert_param(IS_SPI_ALL_INSTANCE(hspi
->Instance
));
457 hspi
->State
= HAL_SPI_STATE_BUSY
;
459 /* Disable the SPI Peripheral Clock */
460 __HAL_SPI_DISABLE(hspi
);
462 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
463 if (hspi
->MspDeInitCallback
== NULL
)
465 hspi
->MspDeInitCallback
= HAL_SPI_MspDeInit
; /* Legacy weak MspDeInit */
468 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
469 hspi
->MspDeInitCallback(hspi
);
471 /* DeInit the low level hardware: GPIO, CLOCK, NVIC... */
472 HAL_SPI_MspDeInit(hspi
);
473 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
475 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
476 hspi
->State
= HAL_SPI_STATE_RESET
;
485 * @brief Initialize the SPI MSP.
486 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
487 * the configuration information for SPI module.
490 __weak
void HAL_SPI_MspInit(SPI_HandleTypeDef
*hspi
)
492 /* Prevent unused argument(s) compilation warning */
495 /* NOTE : This function should not be modified, when the callback is needed,
496 the HAL_SPI_MspInit should be implemented in the user file
501 * @brief De-Initialize the SPI MSP.
502 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
503 * the configuration information for SPI module.
506 __weak
void HAL_SPI_MspDeInit(SPI_HandleTypeDef
*hspi
)
508 /* Prevent unused argument(s) compilation warning */
511 /* NOTE : This function should not be modified, when the callback is needed,
512 the HAL_SPI_MspDeInit should be implemented in the user file
516 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
518 * @brief Register a User SPI Callback
519 * To be used instead of the weak predefined callback
520 * @param hspi Pointer to a SPI_HandleTypeDef structure that contains
521 * the configuration information for the specified SPI.
522 * @param CallbackID ID of the callback to be registered
523 * @param pCallback pointer to the Callback function
526 HAL_StatusTypeDef
HAL_SPI_RegisterCallback(SPI_HandleTypeDef
*hspi
, HAL_SPI_CallbackIDTypeDef CallbackID
, pSPI_CallbackTypeDef pCallback
)
528 HAL_StatusTypeDef status
= HAL_OK
;
530 if (pCallback
== NULL
)
532 /* Update the error code */
533 hspi
->ErrorCode
|= HAL_SPI_ERROR_INVALID_CALLBACK
;
540 if (HAL_SPI_STATE_READY
== hspi
->State
)
544 case HAL_SPI_TX_COMPLETE_CB_ID
:
545 hspi
->TxCpltCallback
= pCallback
;
548 case HAL_SPI_RX_COMPLETE_CB_ID
:
549 hspi
->RxCpltCallback
= pCallback
;
552 case HAL_SPI_TX_RX_COMPLETE_CB_ID
:
553 hspi
->TxRxCpltCallback
= pCallback
;
556 case HAL_SPI_TX_HALF_COMPLETE_CB_ID
:
557 hspi
->TxHalfCpltCallback
= pCallback
;
560 case HAL_SPI_RX_HALF_COMPLETE_CB_ID
:
561 hspi
->RxHalfCpltCallback
= pCallback
;
564 case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID
:
565 hspi
->TxRxHalfCpltCallback
= pCallback
;
568 case HAL_SPI_ERROR_CB_ID
:
569 hspi
->ErrorCallback
= pCallback
;
572 case HAL_SPI_ABORT_CB_ID
:
573 hspi
->AbortCpltCallback
= pCallback
;
576 case HAL_SPI_MSPINIT_CB_ID
:
577 hspi
->MspInitCallback
= pCallback
;
580 case HAL_SPI_MSPDEINIT_CB_ID
:
581 hspi
->MspDeInitCallback
= pCallback
;
585 /* Update the error code */
586 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
588 /* Return error status */
593 else if (HAL_SPI_STATE_RESET
== hspi
->State
)
597 case HAL_SPI_MSPINIT_CB_ID
:
598 hspi
->MspInitCallback
= pCallback
;
601 case HAL_SPI_MSPDEINIT_CB_ID
:
602 hspi
->MspDeInitCallback
= pCallback
;
606 /* Update the error code */
607 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
609 /* Return error status */
616 /* Update the error code */
617 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
619 /* Return error status */
629 * @brief Unregister an SPI Callback
630 * SPI callback is redirected to the weak predefined callback
631 * @param hspi Pointer to a SPI_HandleTypeDef structure that contains
632 * the configuration information for the specified SPI.
633 * @param CallbackID ID of the callback to be unregistered
636 HAL_StatusTypeDef
HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef
*hspi
, HAL_SPI_CallbackIDTypeDef CallbackID
)
638 HAL_StatusTypeDef status
= HAL_OK
;
643 if (HAL_SPI_STATE_READY
== hspi
->State
)
647 case HAL_SPI_TX_COMPLETE_CB_ID
:
648 hspi
->TxCpltCallback
= HAL_SPI_TxCpltCallback
; /* Legacy weak TxCpltCallback */
651 case HAL_SPI_RX_COMPLETE_CB_ID
:
652 hspi
->RxCpltCallback
= HAL_SPI_RxCpltCallback
; /* Legacy weak RxCpltCallback */
655 case HAL_SPI_TX_RX_COMPLETE_CB_ID
:
656 hspi
->TxRxCpltCallback
= HAL_SPI_TxRxCpltCallback
; /* Legacy weak TxRxCpltCallback */
659 case HAL_SPI_TX_HALF_COMPLETE_CB_ID
:
660 hspi
->TxHalfCpltCallback
= HAL_SPI_TxHalfCpltCallback
; /* Legacy weak TxHalfCpltCallback */
663 case HAL_SPI_RX_HALF_COMPLETE_CB_ID
:
664 hspi
->RxHalfCpltCallback
= HAL_SPI_RxHalfCpltCallback
; /* Legacy weak RxHalfCpltCallback */
667 case HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID
:
668 hspi
->TxRxHalfCpltCallback
= HAL_SPI_TxRxHalfCpltCallback
; /* Legacy weak TxRxHalfCpltCallback */
671 case HAL_SPI_ERROR_CB_ID
:
672 hspi
->ErrorCallback
= HAL_SPI_ErrorCallback
; /* Legacy weak ErrorCallback */
675 case HAL_SPI_ABORT_CB_ID
:
676 hspi
->AbortCpltCallback
= HAL_SPI_AbortCpltCallback
; /* Legacy weak AbortCpltCallback */
679 case HAL_SPI_MSPINIT_CB_ID
:
680 hspi
->MspInitCallback
= HAL_SPI_MspInit
; /* Legacy weak MspInit */
683 case HAL_SPI_MSPDEINIT_CB_ID
:
684 hspi
->MspDeInitCallback
= HAL_SPI_MspDeInit
; /* Legacy weak MspDeInit */
688 /* Update the error code */
689 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
691 /* Return error status */
696 else if (HAL_SPI_STATE_RESET
== hspi
->State
)
700 case HAL_SPI_MSPINIT_CB_ID
:
701 hspi
->MspInitCallback
= HAL_SPI_MspInit
; /* Legacy weak MspInit */
704 case HAL_SPI_MSPDEINIT_CB_ID
:
705 hspi
->MspDeInitCallback
= HAL_SPI_MspDeInit
; /* Legacy weak MspDeInit */
709 /* Update the error code */
710 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
712 /* Return error status */
719 /* Update the error code */
720 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_INVALID_CALLBACK
);
722 /* Return error status */
730 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
735 /** @defgroup SPI_Exported_Functions_Group2 IO operation functions
736 * @brief Data transfers functions
739 ==============================================================================
740 ##### IO operation functions #####
741 ===============================================================================
743 This subsection provides a set of functions allowing to manage the SPI
746 [..] The SPI supports master and slave mode :
748 (#) There are two modes of transfer:
749 (##) Blocking mode: The communication is performed in polling mode.
750 The HAL status of all data processing is returned by the same function
751 after finishing transfer.
752 (##) No-Blocking mode: The communication is performed using Interrupts
753 or DMA, These APIs return the HAL status.
754 The end of the data processing will be indicated through the
755 dedicated SPI IRQ when using Interrupt mode or the DMA IRQ when
757 The HAL_SPI_TxCpltCallback(), HAL_SPI_RxCpltCallback() and HAL_SPI_TxRxCpltCallback() user callbacks
758 will be executed respectively at the end of the transmit or Receive process
759 The HAL_SPI_ErrorCallback()user callback will be executed when a communication error is detected
761 (#) APIs provided for these 2 transfer modes (Blocking mode or Non blocking mode using either Interrupt or DMA)
762 exist for 1Line (simplex) and 2Lines (full duplex) modes.
769 * @brief Transmit an amount of data in blocking mode.
770 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
771 * the configuration information for SPI module.
772 * @param pData : pointer to data buffer
773 * @param Size : amount of data to be sent
774 * @param Timeout: Timeout duration
777 HAL_StatusTypeDef
HAL_SPI_Transmit(SPI_HandleTypeDef
*hspi
, const uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
779 #if defined (__GNUC__)
780 __IO
uint16_t *ptxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->TXDR
));
781 #endif /* __GNUC__ */
784 HAL_StatusTypeDef errorcode
= HAL_OK
;
786 /* Check Direction parameter */
787 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_TXONLY(hspi
->Init
.Direction
));
792 /* Init tickstart for timeout management*/
793 tickstart
= HAL_GetTick();
795 if (hspi
->State
!= HAL_SPI_STATE_READY
)
797 errorcode
= HAL_BUSY
;
802 if ((pData
== NULL
) || (Size
== 0UL))
804 errorcode
= HAL_ERROR
;
809 /* Set the transaction information */
810 hspi
->State
= HAL_SPI_STATE_BUSY_TX
;
811 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
812 hspi
->pTxBuffPtr
= (uint8_t *)pData
;
813 hspi
->TxXferSize
= Size
;
814 hspi
->TxXferCount
= Size
;
816 /*Init field not used in handle to zero */
817 hspi
->pRxBuffPtr
= NULL
;
818 hspi
->RxXferSize
= (uint16_t) 0UL;
819 hspi
->RxXferCount
= (uint16_t) 0UL;
823 /* Configure communication direction : 1Line */
824 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
829 /* Set the number of data at current transfer */
830 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
832 /* Enable SPI peripheral */
833 __HAL_SPI_ENABLE(hspi
);
835 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
837 /* Master transfer start */
838 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
841 /* Transmit data in 32 Bit mode */
842 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
844 /* Transmit data in 32 Bit mode */
845 while (hspi
->TxXferCount
> 0UL)
847 /* Wait until TXP flag is set to send data */
848 if (__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
))
850 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
851 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
856 /* Timeout management */
857 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
859 /* Call standard close procedure with error check */
860 SPI_CloseTransfer(hspi
);
862 /* Process Unlocked */
865 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
866 hspi
->State
= HAL_SPI_STATE_READY
;
872 /* Transmit data in 16 Bit mode */
873 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
875 /* Transmit data in 16 Bit mode */
876 while (hspi
->TxXferCount
> 0UL)
878 /* Wait until TXP flag is set to send data */
879 if (__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
))
881 if ((hspi
->TxXferCount
> 1UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_01DATA
))
883 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
884 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
885 hspi
->TxXferCount
-= (uint16_t)2UL;
889 #if defined (__GNUC__)
890 *ptxdr_16bits
= *((uint16_t *)hspi
->pTxBuffPtr
);
892 *((__IO
uint16_t *)&hspi
->Instance
->TXDR
) = *((uint16_t *)hspi
->pTxBuffPtr
);
893 #endif /* __GNUC__ */
894 hspi
->pTxBuffPtr
+= sizeof(uint16_t);
900 /* Timeout management */
901 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
903 /* Call standard close procedure with error check */
904 SPI_CloseTransfer(hspi
);
906 /* Process Unlocked */
909 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
910 hspi
->State
= HAL_SPI_STATE_READY
;
916 /* Transmit data in 8 Bit mode */
919 while (hspi
->TxXferCount
> 0UL)
921 /* Wait until TXP flag is set to send data */
922 if (__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
))
924 if ((hspi
->TxXferCount
> 3UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_03DATA
))
926 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
927 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
928 hspi
->TxXferCount
-= (uint16_t)4UL;
930 else if ((hspi
->TxXferCount
> 1UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_01DATA
))
932 #if defined (__GNUC__)
933 *ptxdr_16bits
= *((uint16_t *)hspi
->pTxBuffPtr
);
935 *((__IO
uint16_t *)&hspi
->Instance
->TXDR
) = *((uint16_t *)hspi
->pTxBuffPtr
);
936 #endif /* __GNUC__ */
937 hspi
->pTxBuffPtr
+= sizeof(uint16_t);
938 hspi
->TxXferCount
-= (uint16_t)2UL;
942 *((__IO
uint8_t *)&hspi
->Instance
->TXDR
) = *((uint8_t *)hspi
->pTxBuffPtr
);
943 hspi
->pTxBuffPtr
+= sizeof(uint8_t);
949 /* Timeout management */
950 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
952 /* Call standard close procedure with error check */
953 SPI_CloseTransfer(hspi
);
955 /* Process Unlocked */
958 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
959 hspi
->State
= HAL_SPI_STATE_READY
;
966 /* Wait for Tx (and CRC) data to be sent */
967 if (SPI_WaitOnFlagUntilTimeout(hspi
, SPI_FLAG_EOT
, RESET
, tickstart
, Timeout
) != HAL_OK
)
969 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_FLAG
);
972 /* Call standard close procedure with error check */
973 SPI_CloseTransfer(hspi
);
975 /* Process Unlocked */
978 hspi
->State
= HAL_SPI_STATE_READY
;
980 if (hspi
->ErrorCode
!= HAL_SPI_ERROR_NONE
)
988 * @brief Receive an amount of data in blocking mode.
989 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
990 * the configuration information for SPI module.
991 * @param pData : pointer to data buffer
992 * @param Size : amount of data to be received
993 * @param Timeout: Timeout duration
996 HAL_StatusTypeDef
HAL_SPI_Receive(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
, uint32_t Timeout
)
999 HAL_StatusTypeDef errorcode
= HAL_OK
;
1000 #if defined (__GNUC__)
1001 __IO
uint16_t *prxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->RXDR
));
1002 #endif /* __GNUC__ */
1004 /* Check Direction parameter */
1005 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_RXONLY(hspi
->Init
.Direction
));
1007 if ((hspi
->Init
.Mode
== SPI_MODE_MASTER
) && (hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
))
1009 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
1010 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1011 return HAL_SPI_TransmitReceive(hspi
, pData
, pData
, Size
, Timeout
);
1014 /* Process Locked */
1017 /* Init tickstart for timeout management*/
1018 tickstart
= HAL_GetTick();
1020 if (hspi
->State
!= HAL_SPI_STATE_READY
)
1022 errorcode
= HAL_BUSY
;
1027 if ((pData
== NULL
) || (Size
== 0UL))
1029 errorcode
= HAL_ERROR
;
1034 /* Set the transaction information */
1035 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
1036 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
1037 hspi
->pRxBuffPtr
= (uint8_t *)pData
;
1038 hspi
->RxXferSize
= Size
;
1039 hspi
->RxXferCount
= Size
;
1041 /*Init field not used in handle to zero */
1042 hspi
->pTxBuffPtr
= NULL
;
1043 hspi
->TxXferSize
= (uint16_t) 0UL;
1044 hspi
->TxXferCount
= (uint16_t) 0UL;
1048 /* Configure communication direction: 1Line */
1049 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
1054 /* Set the number of data at current transfer */
1055 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
1057 /* Enable SPI peripheral */
1058 __HAL_SPI_ENABLE(hspi
);
1060 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
1062 /* Master transfer start */
1063 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
1066 /* Receive data in 32 Bit mode */
1067 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
1070 while (hspi
->RxXferCount
> 0UL)
1072 /* Check the RXWNE/EOT flag */
1073 if ((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_EOT
)) != 0UL)
1075 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1076 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1077 hspi
->RxXferCount
--;
1081 /* Timeout management */
1082 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1084 /* Call standard close procedure with error check */
1085 SPI_CloseTransfer(hspi
);
1087 /* Process Unlocked */
1090 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1091 hspi
->State
= HAL_SPI_STATE_READY
;
1097 /* Receive data in 16 Bit mode */
1098 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
1101 while (hspi
->RxXferCount
> 0UL)
1103 /* Check the RXWNE/FRLVL flag */
1104 if ((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_FRLVL
)) != 0UL)
1106 if ((hspi
->Instance
->SR
& SPI_FLAG_RXWNE
) != 0UL)
1108 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1109 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1110 hspi
->RxXferCount
-= (uint16_t)2UL;
1114 #if defined (__GNUC__)
1115 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
1117 *((uint16_t *)hspi
->pRxBuffPtr
) = *((__IO
uint16_t *)&hspi
->Instance
->RXDR
);
1118 #endif /* __GNUC__ */
1119 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
1120 hspi
->RxXferCount
--;
1125 /* Timeout management */
1126 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1128 /* Call standard close procedure with error check */
1129 SPI_CloseTransfer(hspi
);
1131 /* Process Unlocked */
1134 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1135 hspi
->State
= HAL_SPI_STATE_READY
;
1141 /* Receive data in 8 Bit mode */
1145 while (hspi
->RxXferCount
> 0UL)
1147 /* Check the RXWNE/FRLVL flag */
1148 if ((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_FRLVL
)) != 0UL)
1150 if ((hspi
->Instance
->SR
& SPI_FLAG_RXWNE
) != 0UL)
1152 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1153 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1154 hspi
->RxXferCount
-= (uint16_t)4UL;
1156 else if ((hspi
->Instance
->SR
& SPI_FLAG_FRLVL
) > SPI_RX_FIFO_1PACKET
)
1158 #if defined (__GNUC__)
1159 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
1161 *((uint16_t *)hspi
->pRxBuffPtr
) = *((__IO
uint16_t *)&hspi
->Instance
->RXDR
);
1162 #endif /* __GNUC__ */
1163 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
1164 hspi
->RxXferCount
-= (uint16_t)2UL;
1168 *((uint8_t *)hspi
->pRxBuffPtr
) = *((__IO
uint8_t *)&hspi
->Instance
->RXDR
);
1169 hspi
->pRxBuffPtr
+= sizeof(uint8_t);
1170 hspi
->RxXferCount
--;
1175 /* Timeout management */
1176 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1178 /* Call standard close procedure with error check */
1179 SPI_CloseTransfer(hspi
);
1181 /* Process Unlocked */
1184 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1185 hspi
->State
= HAL_SPI_STATE_READY
;
1192 #if (USE_SPI_CRC != 0UL)
1193 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_ENABLE
)
1195 /* Wait for crc data to be received */
1196 if (SPI_WaitOnFlagUntilTimeout(hspi
, SPI_FLAG_EOT
, RESET
, tickstart
, Timeout
) != HAL_OK
)
1198 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_FLAG
);
1201 #endif /* USE_SPI_CRC */
1203 /* Call standard close procedure with error check */
1204 SPI_CloseTransfer(hspi
);
1206 /* Process Unlocked */
1209 hspi
->State
= HAL_SPI_STATE_READY
;
1211 if (hspi
->ErrorCode
!= HAL_SPI_ERROR_NONE
)
1219 * @brief Transmit and Receive an amount of data in blocking mode.
1220 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1221 * the configuration information for SPI module.
1222 * @param pTxData: pointer to transmission data buffer
1223 * @param pRxData: pointer to reception data buffer
1224 * @param Size : amount of data to be sent and received
1225 * @param Timeout: Timeout duration
1226 * @retval HAL status
1228 HAL_StatusTypeDef
HAL_SPI_TransmitReceive(SPI_HandleTypeDef
*hspi
, const uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
,
1231 HAL_SPI_StateTypeDef tmp_state
;
1232 HAL_StatusTypeDef errorcode
= HAL_OK
;
1233 #if defined (__GNUC__)
1234 __IO
uint16_t *ptxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->TXDR
));
1235 __IO
uint16_t *prxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->RXDR
));
1236 #endif /* __GNUC__ */
1240 uint16_t initial_TxXferCount
;
1241 uint16_t initial_RxXferCount
;
1243 /* Check Direction parameter */
1244 assert_param(IS_SPI_DIRECTION_2LINES(hspi
->Init
.Direction
));
1246 /* Process Locked */
1249 /* Init tickstart for timeout management*/
1250 tickstart
= HAL_GetTick();
1252 initial_TxXferCount
= Size
;
1253 initial_RxXferCount
= Size
;
1254 tmp_state
= hspi
->State
;
1255 tmp_mode
= hspi
->Init
.Mode
;
1257 if (!((tmp_state
== HAL_SPI_STATE_READY
) || \
1258 ((tmp_mode
== SPI_MODE_MASTER
) && (hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
) && (tmp_state
== HAL_SPI_STATE_BUSY_RX
))))
1260 errorcode
= HAL_BUSY
;
1265 if ((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0UL))
1267 errorcode
= HAL_ERROR
;
1272 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1273 if (hspi
->State
!= HAL_SPI_STATE_BUSY_RX
)
1275 hspi
->State
= HAL_SPI_STATE_BUSY_TX_RX
;
1278 /* Set the transaction information */
1279 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
1280 hspi
->pRxBuffPtr
= (uint8_t *)pRxData
;
1281 hspi
->RxXferCount
= Size
;
1282 hspi
->RxXferSize
= Size
;
1283 hspi
->pTxBuffPtr
= (uint8_t *)pTxData
;
1284 hspi
->TxXferCount
= Size
;
1285 hspi
->TxXferSize
= Size
;
1287 /*Init field not used in handle to zero */
1291 /* Set the number of data at current transfer */
1292 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
1294 __HAL_SPI_ENABLE(hspi
);
1296 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
1298 /* Master transfer start */
1299 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
1302 /* Transmit and Receive data in 32 Bit mode */
1303 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
1305 while ((initial_TxXferCount
> 0UL) || (initial_RxXferCount
> 0UL))
1307 /* Check TXP flag */
1308 if ((__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
)) && (initial_TxXferCount
> 0UL))
1310 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
1311 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
1312 hspi
->TxXferCount
--;
1313 initial_TxXferCount
= hspi
->TxXferCount
;
1316 /* Check RXWNE/EOT flag */
1317 if (((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_EOT
)) != 0UL) && (initial_RxXferCount
> 0UL))
1319 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1320 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1321 hspi
->RxXferCount
--;
1322 initial_RxXferCount
= hspi
->RxXferCount
;
1325 /* Timeout management */
1326 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1328 /* Call standard close procedure with error check */
1329 SPI_CloseTransfer(hspi
);
1331 /* Process Unlocked */
1334 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1335 hspi
->State
= HAL_SPI_STATE_READY
;
1340 /* Transmit and Receive data in 16 Bit mode */
1341 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
1343 while ((initial_TxXferCount
> 0UL) || (initial_RxXferCount
> 0UL))
1345 /* Check TXP flag */
1346 if (__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
) && (initial_TxXferCount
> 0UL))
1348 if ((initial_TxXferCount
> 1UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_01DATA
))
1350 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
1351 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
1352 hspi
->TxXferCount
-= (uint16_t)2UL;
1353 initial_TxXferCount
= hspi
->TxXferCount
;
1357 #if defined (__GNUC__)
1358 *ptxdr_16bits
= *((uint16_t *)hspi
->pTxBuffPtr
);
1360 *((__IO
uint16_t *)&hspi
->Instance
->TXDR
) = *((uint16_t *)hspi
->pTxBuffPtr
);
1361 #endif /* __GNUC__ */
1362 hspi
->pTxBuffPtr
+= sizeof(uint16_t);
1363 hspi
->TxXferCount
--;
1364 initial_TxXferCount
= hspi
->TxXferCount
;
1368 /* Check RXWNE/FRLVL flag */
1369 if (((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_FRLVL
)) != 0UL) && (initial_RxXferCount
> 0UL))
1371 if ((hspi
->Instance
->SR
& SPI_FLAG_RXWNE
) != 0UL)
1373 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1374 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1375 hspi
->RxXferCount
-= (uint16_t)2UL;
1376 initial_RxXferCount
= hspi
->RxXferCount
;
1380 #if defined (__GNUC__)
1381 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
1383 *((uint16_t *)hspi
->pRxBuffPtr
) = *((__IO
uint16_t *)&hspi
->Instance
->RXDR
);
1384 #endif /* __GNUC__ */
1385 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
1386 hspi
->RxXferCount
--;
1387 initial_RxXferCount
= hspi
->RxXferCount
;
1391 /* Timeout management */
1392 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1394 /* Call standard close procedure with error check */
1395 SPI_CloseTransfer(hspi
);
1397 /* Process Unlocked */
1400 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1401 hspi
->State
= HAL_SPI_STATE_READY
;
1406 /* Transmit and Receive data in 8 Bit mode */
1409 while ((initial_TxXferCount
> 0UL) || (initial_RxXferCount
> 0UL))
1411 /* check TXP flag */
1412 if ((__HAL_SPI_GET_FLAG(hspi
, SPI_FLAG_TXP
)) && (initial_TxXferCount
> 0UL))
1414 if ((initial_TxXferCount
> 3UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_03DATA
))
1416 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
1417 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
1418 hspi
->TxXferCount
-= (uint16_t)4UL;
1419 initial_TxXferCount
= hspi
->TxXferCount
;
1421 else if ((initial_TxXferCount
> 1UL) && (hspi
->Init
.FifoThreshold
> SPI_FIFO_THRESHOLD_01DATA
))
1423 #if defined (__GNUC__)
1424 *ptxdr_16bits
= *((uint16_t *)hspi
->pTxBuffPtr
);
1426 *((__IO
uint16_t *)&hspi
->Instance
->TXDR
) = *((uint16_t *)hspi
->pTxBuffPtr
);
1427 #endif /* __GNUC__ */
1428 hspi
->pTxBuffPtr
+= sizeof(uint16_t);
1429 hspi
->TxXferCount
-= (uint16_t)2UL;
1430 initial_TxXferCount
= hspi
->TxXferCount
;
1434 *((__IO
uint8_t *)&hspi
->Instance
->TXDR
) = *((uint8_t *)hspi
->pTxBuffPtr
);
1435 hspi
->pTxBuffPtr
+= sizeof(uint8_t);
1436 hspi
->TxXferCount
--;
1437 initial_TxXferCount
= hspi
->TxXferCount
;
1441 /* Wait until RXWNE/FRLVL flag is reset */
1442 if (((hspi
->Instance
->SR
& (SPI_FLAG_RXWNE
| SPI_FLAG_FRLVL
)) != 0UL) && (initial_RxXferCount
> 0UL))
1444 if ((hspi
->Instance
->SR
& SPI_FLAG_RXWNE
) != 0UL)
1446 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
1447 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
1448 hspi
->RxXferCount
-= (uint16_t)4UL;
1449 initial_RxXferCount
= hspi
->RxXferCount
;
1451 else if ((hspi
->Instance
->SR
& SPI_FLAG_FRLVL
) > SPI_RX_FIFO_1PACKET
)
1453 #if defined (__GNUC__)
1454 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
1456 *((uint16_t *)hspi
->pRxBuffPtr
) = *((__IO
uint16_t *)&hspi
->Instance
->RXDR
);
1457 #endif /* __GNUC__ */
1458 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
1459 hspi
->RxXferCount
-= (uint16_t)2UL;
1460 initial_RxXferCount
= hspi
->RxXferCount
;
1464 *((uint8_t *)hspi
->pRxBuffPtr
) = *((__IO
uint8_t *)&hspi
->Instance
->RXDR
);
1465 hspi
->pRxBuffPtr
+= sizeof(uint8_t);
1466 hspi
->RxXferCount
--;
1467 initial_RxXferCount
= hspi
->RxXferCount
;
1471 /* Timeout management */
1472 if ((((HAL_GetTick() - tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
1474 /* Call standard close procedure with error check */
1475 SPI_CloseTransfer(hspi
);
1477 /* Process Unlocked */
1480 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_TIMEOUT
);
1481 hspi
->State
= HAL_SPI_STATE_READY
;
1487 /* Wait for Tx/Rx (and CRC) data to be sent/received */
1488 if (SPI_WaitOnFlagUntilTimeout(hspi
, SPI_FLAG_EOT
, RESET
, tickstart
, Timeout
) != HAL_OK
)
1490 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_FLAG
);
1493 /* Call standard close procedure with error check */
1494 SPI_CloseTransfer(hspi
);
1496 /* Process Unlocked */
1499 hspi
->State
= HAL_SPI_STATE_READY
;
1501 if (hspi
->ErrorCode
!= HAL_SPI_ERROR_NONE
)
1509 * @brief Transmit an amount of data in non-blocking mode with Interrupt.
1510 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1511 * the configuration information for SPI module.
1512 * @param pData: pointer to data buffer
1513 * @param Size : amount of data to be sent
1514 * @retval HAL status
1516 HAL_StatusTypeDef
HAL_SPI_Transmit_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
1518 HAL_StatusTypeDef errorcode
= HAL_OK
;
1520 /* Check Direction parameter */
1521 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_TXONLY(hspi
->Init
.Direction
));
1523 /* Process Locked */
1526 if ((pData
== NULL
) || (Size
== 0UL))
1528 errorcode
= HAL_ERROR
;
1533 if (hspi
->State
!= HAL_SPI_STATE_READY
)
1535 errorcode
= HAL_BUSY
;
1540 /* Set the transaction information */
1541 hspi
->State
= HAL_SPI_STATE_BUSY_TX
;
1542 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
1543 hspi
->pTxBuffPtr
= (uint8_t *)pData
;
1544 hspi
->TxXferSize
= Size
;
1545 hspi
->TxXferCount
= Size
;
1547 /* Init field not used in handle to zero */
1548 hspi
->pRxBuffPtr
= NULL
;
1549 hspi
->RxXferSize
= (uint16_t) 0UL;
1550 hspi
->RxXferCount
= (uint16_t) 0UL;
1553 /* Set the function for IT treatment */
1554 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
1556 hspi
->TxISR
= SPI_TxISR_32BIT
;
1558 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
1560 hspi
->TxISR
= SPI_TxISR_16BIT
;
1564 hspi
->TxISR
= SPI_TxISR_8BIT
;
1567 /* Configure communication direction : 1Line */
1568 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
1573 /* Set the number of data at current transfer */
1574 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
1576 /* Enable SPI peripheral */
1577 __HAL_SPI_ENABLE(hspi
);
1579 /* Enable EOT, TXP, FRE, MODF, UDR and TSERF interrupts */
1580 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_EOT
| SPI_IT_TXP
| SPI_IT_UDR
| SPI_IT_FRE
| SPI_IT_MODF
| SPI_IT_TSERF
));
1582 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
1584 /* Master transfer start */
1585 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
1593 * @brief Receive an amount of data in non-blocking mode with Interrupt.
1594 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1595 * the configuration information for SPI module.
1596 * @param pData: pointer to data buffer
1597 * @param Size : amount of data to be sent
1598 * @retval HAL status
1600 HAL_StatusTypeDef
HAL_SPI_Receive_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
1602 HAL_StatusTypeDef errorcode
= HAL_OK
;
1604 /* Check Direction parameter */
1605 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_RXONLY(hspi
->Init
.Direction
));
1607 if ((hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
) && (hspi
->Init
.Mode
== SPI_MODE_MASTER
))
1609 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
1610 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
1611 return HAL_SPI_TransmitReceive_IT(hspi
, pData
, pData
, Size
);
1614 /* Process Locked */
1617 if (hspi
->State
!= HAL_SPI_STATE_READY
)
1619 errorcode
= HAL_BUSY
;
1624 if ((pData
== NULL
) || (Size
== 0UL))
1626 errorcode
= HAL_ERROR
;
1631 /* Set the transaction information */
1632 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
1633 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
1634 hspi
->pRxBuffPtr
= (uint8_t *)pData
;
1635 hspi
->RxXferSize
= Size
;
1636 hspi
->RxXferCount
= Size
;
1638 /* Init field not used in handle to zero */
1639 hspi
->pTxBuffPtr
= NULL
;
1640 hspi
->TxXferSize
= (uint16_t) 0UL;
1641 hspi
->TxXferCount
= (uint16_t) 0UL;
1644 /* Set the function for IT treatment */
1645 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
1647 hspi
->RxISR
= SPI_RxISR_32BIT
;
1649 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
1651 hspi
->RxISR
= SPI_RxISR_16BIT
;
1655 hspi
->RxISR
= SPI_RxISR_8BIT
;
1658 /* Configure communication direction : 1Line */
1659 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
1664 /* Note : The SPI must be enabled after unlocking current process
1665 to avoid the risk of SPI interrupt handle execution before current
1668 /* Set the number of data at current transfer */
1669 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
1671 /* Enable SPI peripheral */
1672 __HAL_SPI_ENABLE(hspi
);
1674 /* Enable EOT, RXP, OVR, FRE, MODF and TSERF interrupts */
1675 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_EOT
| SPI_IT_RXP
| SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_MODF
| SPI_IT_TSERF
));
1677 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
1679 /* Master transfer start */
1680 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
1683 /* Process Unlocked */
1689 * @brief Transmit and Receive an amount of data in non-blocking mode with Interrupt.
1690 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1691 * the configuration information for SPI module.
1692 * @param pTxData: pointer to transmission data buffer
1693 * @param pRxData: pointer to reception data buffer
1694 * @param Size : amount of data to be sent and received
1695 * @retval HAL status
1697 HAL_StatusTypeDef
HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
)
1699 HAL_SPI_StateTypeDef tmp_state
;
1700 HAL_StatusTypeDef errorcode
= HAL_OK
;
1704 /* Check Direction parameter */
1705 assert_param(IS_SPI_DIRECTION_2LINES(hspi
->Init
.Direction
));
1707 /* Process locked */
1710 /* Init temporary variables */
1711 tmp_state
= hspi
->State
;
1712 tmp_mode
= hspi
->Init
.Mode
;
1714 if (!((tmp_state
== HAL_SPI_STATE_READY
) || \
1715 ((tmp_mode
== SPI_MODE_MASTER
) && (hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
) && (tmp_state
== HAL_SPI_STATE_BUSY_RX
))))
1717 errorcode
= HAL_BUSY
;
1722 if ((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0UL))
1724 errorcode
= HAL_ERROR
;
1729 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
1730 if (hspi
->State
!= HAL_SPI_STATE_BUSY_RX
)
1732 hspi
->State
= HAL_SPI_STATE_BUSY_TX_RX
;
1735 /* Set the transaction information */
1736 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
1737 hspi
->pTxBuffPtr
= (uint8_t *)pTxData
;
1738 hspi
->TxXferSize
= Size
;
1739 hspi
->TxXferCount
= Size
;
1740 hspi
->pRxBuffPtr
= (uint8_t *)pRxData
;
1741 hspi
->RxXferSize
= Size
;
1742 hspi
->RxXferCount
= Size
;
1744 /* Set the function for IT treatment */
1745 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
1747 hspi
->TxISR
= SPI_TxISR_32BIT
;
1748 hspi
->RxISR
= SPI_RxISR_32BIT
;
1750 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
1752 hspi
->RxISR
= SPI_RxISR_16BIT
;
1753 hspi
->TxISR
= SPI_TxISR_16BIT
;
1757 hspi
->RxISR
= SPI_RxISR_8BIT
;
1758 hspi
->TxISR
= SPI_TxISR_8BIT
;
1761 /* Set the number of data at current transfer */
1762 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
1764 /* Enable SPI peripheral */
1765 __HAL_SPI_ENABLE(hspi
);
1767 /* Enable EOT, RXP, TXP, DXP, UDR, OVR, FRE, MODF and TSERF interrupts */
1768 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_EOT
| SPI_IT_RXP
| SPI_IT_TXP
| SPI_IT_DXP
| SPI_IT_UDR
| SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_MODF
| SPI_IT_TSERF
));
1770 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
1772 /* Master transfer start */
1773 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
1776 /* Process Unlocked */
1781 #if defined(USE_SPI_RELOAD_TRANSFER)
1783 * @brief Transmit an additional amount of data in blocking mode.
1784 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1785 * the configuration information for SPI module.
1786 * @param pData: pointer to data buffer
1787 * @param Size : amount of data to be sent
1788 * @retval HAL status
1790 HAL_StatusTypeDef
HAL_SPI_Reload_Transmit_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
1792 HAL_StatusTypeDef errorcode
= HAL_OK
;
1793 HAL_SPI_StateTypeDef tmp_state
;
1795 /* Lock the process */
1798 if ((pData
== NULL
) || (Size
== 0UL))
1800 errorcode
= HAL_ERROR
;
1805 if (hspi
->State
== HAL_SPI_STATE_BUSY_TX
)
1807 /* check if there is already a request to reload */
1808 if (hspi
->Reload
.Requested
== 1UL)
1810 errorcode
= HAL_ERROR
;
1815 /* Insert the new number of data to be sent just after the current one */
1816 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, (Size
& 0xFFFFFFFFUL
) << 16UL);
1818 /* Set the transaction information */
1819 hspi
->Reload
.Requested
= 1UL;
1820 hspi
->Reload
.pTxBuffPtr
= (uint8_t *)pData
;
1821 hspi
->Reload
.TxXferSize
= Size
;
1823 tmp_state
= hspi
->State
;
1825 /* Check if the current transmit is already completed */
1826 if (((hspi
->Instance
->CR2
& SPI_CR2_TSER
) != 0UL) && (tmp_state
== HAL_SPI_STATE_READY
))
1828 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TSERF
);
1829 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, 0UL);
1830 hspi
->Reload
.Requested
= 0UL;
1831 errorcode
= HAL_ERROR
;
1838 errorcode
= HAL_ERROR
;
1845 #endif /* USE_HSPI_RELOAD_TRANSFER */
1847 #if defined(USE_SPI_RELOAD_TRANSFER)
1849 * @brief Receive an additional amount of data in blocking mode.
1850 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1851 * the configuration information for SPI module.
1852 * @param pData: pointer to data buffer
1853 * @param Size : amount of data to be sent
1854 * @retval HAL status
1856 HAL_StatusTypeDef
HAL_SPI_Reload_Receive_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
1858 HAL_StatusTypeDef errorcode
= HAL_OK
;
1859 HAL_SPI_StateTypeDef tmp_state
;
1861 /* Lock the process */
1864 if ((pData
== NULL
) || (Size
== 0UL))
1866 errorcode
= HAL_ERROR
;
1871 if (hspi
->State
== HAL_SPI_STATE_BUSY_RX
)
1873 /* check if there is already a request to reload */
1874 if (hspi
->Reload
.Requested
== 1UL)
1876 errorcode
= HAL_ERROR
;
1881 /* Insert the new number of data that will be received just after the current one */
1882 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, (Size
& 0xFFFFFFFFUL
) << 16UL);
1884 /* Set the transaction information */
1885 hspi
->Reload
.Requested
= 1UL;
1886 hspi
->Reload
.pRxBuffPtr
= (uint8_t *)pData
;
1887 hspi
->Reload
.RxXferSize
= Size
;
1889 tmp_state
= hspi
->State
;
1891 /* Check if the current reception is already completed */
1892 if (((hspi
->Instance
->CR2
& SPI_CR2_TSER
) != 0UL) && (tmp_state
== HAL_SPI_STATE_READY
))
1894 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TSERF
);
1895 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, 0UL);
1896 hspi
->Reload
.Requested
= 0UL;
1897 errorcode
= HAL_ERROR
;
1904 errorcode
= HAL_ERROR
;
1911 #endif /* USE_HSPI_RELOAD_TRANSFER */
1913 #if defined(USE_SPI_RELOAD_TRANSFER)
1915 * @brief Transmit and receive an additional amount of data in blocking mode.
1916 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1917 * the configuration information for SPI module.
1918 * @param pTxData: pointer to transmission data buffer
1919 * @param pRxData: pointer to reception data buffer
1920 * @param Size : amount of data to be sent and received
1921 * @retval HAL status
1923 HAL_StatusTypeDef
HAL_SPI_Reload_TransmitReceive_IT(SPI_HandleTypeDef
*hspi
, uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
)
1925 HAL_StatusTypeDef errorcode
= HAL_OK
;
1926 HAL_SPI_StateTypeDef tmp_state
;
1928 /* Lock the process */
1931 if ((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0UL))
1933 errorcode
= HAL_ERROR
;
1938 if (hspi
->State
== HAL_SPI_STATE_BUSY_TX_RX
)
1940 /* check if there is already a request to reload */
1941 if (hspi
->Reload
.Requested
== 1UL)
1943 errorcode
= HAL_ERROR
;
1948 /* Insert the new number of data that will be sent and received just after the current one */
1949 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, (Size
& 0xFFFFFFFFUL
) << 16UL);
1951 /* Set the transaction information */
1952 hspi
->Reload
.Requested
= 1UL;
1953 hspi
->Reload
.pTxBuffPtr
= (uint8_t *)pTxData
;
1954 hspi
->Reload
.TxXferSize
= Size
;
1955 hspi
->Reload
.pRxBuffPtr
= (uint8_t *)pRxData
;
1956 hspi
->Reload
.RxXferSize
= Size
;
1958 tmp_state
= hspi
->State
;
1960 /* Check if the current transmit is already completed */
1961 if (((hspi
->Instance
->CR2
& SPI_CR2_TSER
) != 0UL) && (tmp_state
== HAL_SPI_STATE_READY
))
1963 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TSERF
);
1964 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSER
, 0UL);
1965 hspi
->Reload
.Requested
= 0UL;
1966 errorcode
= HAL_ERROR
;
1973 errorcode
= HAL_ERROR
;
1980 #endif /* USE_HSPI_RELOAD_TRANSFER */
1983 * @brief Transmit an amount of data in non-blocking mode with DMA.
1984 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
1985 * the configuration information for SPI module.
1986 * @param pData: pointer to data buffer
1987 * @param Size : amount of data to be sent
1988 * @retval HAL status
1990 HAL_StatusTypeDef
HAL_SPI_Transmit_DMA(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
1992 HAL_StatusTypeDef errorcode
= HAL_OK
;
1994 /* Check Direction parameter */
1995 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_TXONLY(hspi
->Init
.Direction
));
1997 /* Process Locked */
2000 if (hspi
->State
!= HAL_SPI_STATE_READY
)
2002 errorcode
= HAL_BUSY
;
2007 if ((pData
== NULL
) || (Size
== 0UL))
2009 errorcode
= HAL_ERROR
;
2014 /* Set the transaction information */
2015 hspi
->State
= HAL_SPI_STATE_BUSY_TX
;
2016 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
2017 hspi
->pTxBuffPtr
= (uint8_t *)pData
;
2018 hspi
->TxXferSize
= Size
;
2019 hspi
->TxXferCount
= Size
;
2021 /* Init field not used in handle to zero */
2022 hspi
->pRxBuffPtr
= NULL
;
2025 hspi
->RxXferSize
= (uint16_t)0UL;
2026 hspi
->RxXferCount
= (uint16_t)0UL;
2028 /* Configure communication direction : 1Line */
2029 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
2034 /* Packing mode management is enabled by the DMA settings */
2035 if (((hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
) && (hspi
->hdmatx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
)) || \
2036 ((hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
) && ((hspi
->hdmatx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_HALFWORD
) && \
2037 (hspi
->hdmatx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
))))
2039 /* Restriction the DMA data received is not allowed in this mode */
2040 errorcode
= HAL_ERROR
;
2045 /* Adjust XferCount according to DMA alignment / Data size */
2046 if (hspi
->Init
.DataSize
<= SPI_DATASIZE_8BIT
)
2048 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_HALFWORD
)
2050 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 1UL) >> 1UL;
2052 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2054 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 3UL) >> 2UL;
2057 else if (hspi
->Init
.DataSize
<= SPI_DATASIZE_16BIT
)
2059 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2061 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 1UL) >> 1UL;
2066 /* Adjustment done */
2069 /* Set the SPI TxDMA Half transfer complete callback */
2070 hspi
->hdmatx
->XferHalfCpltCallback
= SPI_DMAHalfTransmitCplt
;
2072 /* Set the SPI TxDMA transfer complete callback */
2073 hspi
->hdmatx
->XferCpltCallback
= SPI_DMATransmitCplt
;
2075 /* Set the DMA error callback */
2076 hspi
->hdmatx
->XferErrorCallback
= SPI_DMAError
;
2078 /* Set the DMA AbortCpltCallback */
2079 hspi
->hdmatx
->XferAbortCallback
= NULL
;
2081 /* Clear TXDMAEN bit*/
2082 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
);
2084 /* Enable the Tx DMA Stream/Channel */
2085 if (HAL_OK
!= HAL_DMA_Start_IT(hspi
->hdmatx
, (uint32_t)hspi
->pTxBuffPtr
, (uint32_t)&hspi
->Instance
->TXDR
, hspi
->TxXferCount
))
2087 /* Update SPI error code */
2088 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_DMA
);
2089 errorcode
= HAL_ERROR
;
2090 hspi
->State
= HAL_SPI_STATE_READY
;
2094 /* Set the number of data at current transfer */
2095 if (hspi
->hdmatx
->Init
.Mode
== DMA_CIRCULAR
)
2097 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, 0UL);
2101 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
2104 /* Enable Tx DMA Request */
2105 SET_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
);
2107 /* Enable the SPI Error Interrupt Bit */
2108 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_UDR
| SPI_IT_FRE
| SPI_IT_MODF
));
2110 /* Enable SPI peripheral */
2111 __HAL_SPI_ENABLE(hspi
);
2113 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
2115 /* Master transfer start */
2116 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
2119 /* Process Unlocked */
2125 * @brief Receive an amount of data in non-blocking mode with DMA.
2126 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
2127 * the configuration information for SPI module.
2128 * @param pData: pointer to data buffer
2129 * @param Size : amount of data to be sent
2130 * @note When the CRC feature is enabled the pData Length must be Size + 1.
2131 * @retval HAL status
2133 HAL_StatusTypeDef
HAL_SPI_Receive_DMA(SPI_HandleTypeDef
*hspi
, uint8_t *pData
, uint16_t Size
)
2135 HAL_StatusTypeDef errorcode
= HAL_OK
;
2137 /* Check Direction parameter */
2138 assert_param(IS_SPI_DIRECTION_2LINES_OR_1LINE_2LINES_RXONLY(hspi
->Init
.Direction
));
2140 if ((hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
) && (hspi
->Init
.Mode
== SPI_MODE_MASTER
))
2142 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
2143 /* Call transmit-receive function to send Dummy data on Tx line and generate clock on CLK line */
2144 return HAL_SPI_TransmitReceive_DMA(hspi
, pData
, pData
, Size
);
2147 /* Process Locked */
2150 if (hspi
->State
!= HAL_SPI_STATE_READY
)
2152 errorcode
= HAL_BUSY
;
2157 if ((pData
== NULL
) || (Size
== 0UL))
2159 errorcode
= HAL_ERROR
;
2164 /* Set the transaction information */
2165 hspi
->State
= HAL_SPI_STATE_BUSY_RX
;
2166 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
2167 hspi
->pRxBuffPtr
= (uint8_t *)pData
;
2168 hspi
->RxXferSize
= Size
;
2169 hspi
->RxXferCount
= Size
;
2171 /*Init field not used in handle to zero */
2174 hspi
->TxXferSize
= (uint16_t) 0UL;
2175 hspi
->TxXferCount
= (uint16_t) 0UL;
2177 /* Configure communication direction : 1Line */
2178 if (hspi
->Init
.Direction
== SPI_DIRECTION_1LINE
)
2183 /* Packing mode management is enabled by the DMA settings */
2184 if (((hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
) && (hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
)) || \
2185 ((hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
) && ((hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_HALFWORD
) && \
2186 (hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
))))
2188 /* Restriction the DMA data received is not allowed in this mode */
2189 errorcode
= HAL_ERROR
;
2194 /* Clear RXDMAEN bit */
2195 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_RXDMAEN
);
2197 /* Adjust XferCount according to DMA alignment / Data size */
2198 if (hspi
->Init
.DataSize
<= SPI_DATASIZE_8BIT
)
2200 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_HALFWORD
)
2202 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 1UL) >> 1UL;
2204 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2206 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 3UL) >> 2UL;
2209 else if (hspi
->Init
.DataSize
<= SPI_DATASIZE_16BIT
)
2211 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2213 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 1UL) >> 1UL;
2218 /* Adjustment done */
2221 /* Set the SPI RxDMA Half transfer complete callback */
2222 hspi
->hdmarx
->XferHalfCpltCallback
= SPI_DMAHalfReceiveCplt
;
2224 /* Set the SPI Rx DMA transfer complete callback */
2225 hspi
->hdmarx
->XferCpltCallback
= SPI_DMAReceiveCplt
;
2227 /* Set the DMA error callback */
2228 hspi
->hdmarx
->XferErrorCallback
= SPI_DMAError
;
2230 /* Set the DMA AbortCpltCallback */
2231 hspi
->hdmarx
->XferAbortCallback
= NULL
;
2233 /* Enable the Rx DMA Stream/Channel */
2234 if (HAL_OK
!= HAL_DMA_Start_IT(hspi
->hdmarx
, (uint32_t)&hspi
->Instance
->RXDR
, (uint32_t)hspi
->pRxBuffPtr
, hspi
->RxXferCount
))
2236 /* Update SPI error code */
2237 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_DMA
);
2238 errorcode
= HAL_ERROR
;
2239 hspi
->State
= HAL_SPI_STATE_READY
;
2243 /* Set the number of data at current transfer */
2244 if (hspi
->hdmarx
->Init
.Mode
== DMA_CIRCULAR
)
2246 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, 0UL);
2250 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
2253 /* Enable Rx DMA Request */
2254 SET_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_RXDMAEN
);
2256 /* Enable the SPI Error Interrupt Bit */
2257 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_MODF
));
2259 /* Enable SPI peripheral */
2260 __HAL_SPI_ENABLE(hspi
);
2262 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
2264 /* Master transfer start */
2265 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
2268 /* Process Unlocked */
2274 * @brief Transmit and Receive an amount of data in non-blocking mode with DMA.
2275 * @param hspi : pointer to a SPI_HandleTypeDef structure that contains
2276 * the configuration information for SPI module.
2277 * @param pTxData: pointer to transmission data buffer
2278 * @param pRxData: pointer to reception data buffer
2279 * @param Size : amount of data to be sent
2280 * @note When the CRC feature is enabled the pRxData Length must be Size + 1
2281 * @retval HAL status
2283 HAL_StatusTypeDef
HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef
*hspi
, uint8_t *pTxData
, uint8_t *pRxData
,
2286 HAL_SPI_StateTypeDef tmp_state
;
2287 HAL_StatusTypeDef errorcode
= HAL_OK
;
2291 /* Check Direction parameter */
2292 assert_param(IS_SPI_DIRECTION_2LINES(hspi
->Init
.Direction
));
2294 /* Process locked */
2297 /* Init temporary variables */
2298 tmp_state
= hspi
->State
;
2299 tmp_mode
= hspi
->Init
.Mode
;
2301 if (!(((tmp_mode
== SPI_MODE_MASTER
) && (hspi
->Init
.Direction
== SPI_DIRECTION_2LINES
) && (tmp_state
== HAL_SPI_STATE_BUSY_RX
)) || (tmp_state
== HAL_SPI_STATE_READY
)))
2303 errorcode
= HAL_BUSY
;
2308 if ((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0UL))
2310 errorcode
= HAL_ERROR
;
2315 /* Don't overwrite in case of HAL_SPI_STATE_BUSY_RX */
2316 if (hspi
->State
!= HAL_SPI_STATE_BUSY_RX
)
2318 hspi
->State
= HAL_SPI_STATE_BUSY_TX_RX
;
2321 /* Set the transaction information */
2322 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
2323 hspi
->pTxBuffPtr
= (uint8_t *)pTxData
;
2324 hspi
->TxXferSize
= Size
;
2325 hspi
->TxXferCount
= Size
;
2326 hspi
->pRxBuffPtr
= (uint8_t *)pRxData
;
2327 hspi
->RxXferSize
= Size
;
2328 hspi
->RxXferCount
= Size
;
2330 /* Init field not used in handle to zero */
2334 /* Reset the Tx/Rx DMA bits */
2335 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
);
2337 /* Packing mode management is enabled by the DMA settings */
2338 if (((hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
) && (hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
)) || \
2339 ((hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
) && ((hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_HALFWORD
) && \
2340 (hspi
->hdmarx
->Init
.MemDataAlignment
!= DMA_MDATAALIGN_WORD
))))
2342 /* Restriction the DMA data received is not allowed in this mode */
2343 errorcode
= HAL_ERROR
;
2344 /* Process Unlocked */
2349 /* Adjust XferCount according to DMA alignment / Data size */
2350 if (hspi
->Init
.DataSize
<= SPI_DATASIZE_8BIT
)
2352 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_HALFWORD
)
2354 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 1UL) >> 1UL;
2356 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2358 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 3UL) >> 2UL;
2360 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_HALFWORD
)
2362 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 1UL) >> 1UL;
2364 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2366 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 3UL) >> 2UL;
2369 else if (hspi
->Init
.DataSize
<= SPI_DATASIZE_16BIT
)
2371 if (hspi
->hdmatx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2373 hspi
->TxXferCount
= (hspi
->TxXferCount
+ (uint16_t) 1UL) >> 1UL;
2375 if (hspi
->hdmarx
->Init
.MemDataAlignment
== DMA_MDATAALIGN_WORD
)
2377 hspi
->RxXferCount
= (hspi
->RxXferCount
+ (uint16_t) 1UL) >> 1UL;
2382 /* Adjustment done */
2385 /* Check if we are in Rx only or in Rx/Tx Mode and configure the DMA transfer complete callback */
2386 if (hspi
->State
== HAL_SPI_STATE_BUSY_RX
)
2388 /* Set the SPI Rx DMA Half transfer complete callback */
2389 hspi
->hdmarx
->XferHalfCpltCallback
= SPI_DMAHalfReceiveCplt
;
2390 hspi
->hdmarx
->XferCpltCallback
= SPI_DMAReceiveCplt
;
2394 /* Set the SPI Tx/Rx DMA Half transfer complete callback */
2395 hspi
->hdmarx
->XferHalfCpltCallback
= SPI_DMAHalfTransmitReceiveCplt
;
2396 hspi
->hdmarx
->XferCpltCallback
= SPI_DMATransmitReceiveCplt
;
2399 /* Set the DMA error callback */
2400 hspi
->hdmarx
->XferErrorCallback
= SPI_DMAError
;
2402 /* Set the DMA AbortCallback */
2403 hspi
->hdmarx
->XferAbortCallback
= NULL
;
2405 /* Enable the Rx DMA Stream/Channel */
2406 if (HAL_OK
!= HAL_DMA_Start_IT(hspi
->hdmarx
, (uint32_t)&hspi
->Instance
->RXDR
, (uint32_t)hspi
->pRxBuffPtr
, hspi
->RxXferCount
))
2408 /* Update SPI error code */
2409 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_DMA
);
2410 errorcode
= HAL_ERROR
;
2411 hspi
->State
= HAL_SPI_STATE_READY
;
2415 /* Enable Rx DMA Request */
2416 SET_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_RXDMAEN
);
2418 /* Set the SPI Tx DMA transfer complete callback as NULL because the communication closing
2419 is performed in DMA reception complete callback */
2420 hspi
->hdmatx
->XferHalfCpltCallback
= NULL
;
2421 hspi
->hdmatx
->XferCpltCallback
= NULL
;
2422 hspi
->hdmatx
->XferErrorCallback
= NULL
;
2423 hspi
->hdmatx
->XferAbortCallback
= NULL
;
2425 /* Enable the Tx DMA Stream/Channel */
2426 if (HAL_OK
!= HAL_DMA_Start_IT(hspi
->hdmatx
, (uint32_t)hspi
->pTxBuffPtr
, (uint32_t)&hspi
->Instance
->TXDR
, hspi
->TxXferCount
))
2428 /* Update SPI error code */
2429 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_DMA
);
2430 errorcode
= HAL_ERROR
;
2431 hspi
->State
= HAL_SPI_STATE_READY
;
2435 if (hspi
->hdmatx
->Init
.Mode
== DMA_CIRCULAR
)
2437 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, 0UL);
2441 MODIFY_REG(hspi
->Instance
->CR2
, SPI_CR2_TSIZE
, Size
);
2444 /* Enable Tx DMA Request */
2445 SET_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
);
2447 /* Enable the SPI Error Interrupt Bit */
2448 __HAL_SPI_ENABLE_IT(hspi
, (SPI_IT_OVR
| SPI_IT_UDR
| SPI_IT_FRE
| SPI_IT_MODF
));
2450 /* Enable SPI peripheral */
2451 __HAL_SPI_ENABLE(hspi
);
2453 if (hspi
->Init
.Mode
== SPI_MODE_MASTER
)
2455 /* Master transfer start */
2456 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSTART
);
2459 /* Process Unlocked */
2465 * @brief Abort ongoing transfer (blocking mode).
2466 * @param hspi SPI handle.
2467 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
2468 * started in Interrupt or DMA mode.
2469 * @note This procedure performs following operations :
2470 * + Disable SPI Interrupts (depending of transfer direction)
2471 * + Disable the DMA transfer in the peripheral register (if enabled)
2472 * + Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
2473 * + Set handle State to READY.
2474 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
2475 * @retval HAL status
2477 HAL_StatusTypeDef
HAL_SPI_Abort(SPI_HandleTypeDef
*hspi
)
2479 HAL_StatusTypeDef errorcode
;
2481 __IO
uint32_t count
;
2483 /* Process locked */
2486 /* Set hspi->state to aborting to avoid any interaction */
2487 hspi
->State
= HAL_SPI_STATE_ABORT
;
2489 /* Initialized local variable */
2491 count
= SPI_DEFAULT_TIMEOUT
* (SystemCoreClock
/ 24UL / 1000UL);
2493 /* If master communication on going, make sure current frame is done before closing the connection */
2494 if (HAL_IS_BIT_SET(hspi
->Instance
->CR1
, SPI_CR1_CSTART
))
2496 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSUSP
);
2502 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_ABORT
);
2506 while (HAL_IS_BIT_SET(hspi
->Instance
->CR1
, SPI_CR1_CSTART
));
2509 /* Disable the SPI DMA Tx request if enabled */
2510 if (HAL_IS_BIT_SET(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
))
2512 if (hspi
->hdmatx
!= NULL
)
2514 /* Abort the SPI DMA Tx Stream/Channel : use blocking DMA Abort API (no callback) */
2515 hspi
->hdmatx
->XferAbortCallback
= NULL
;
2517 /* Abort DMA Tx Handle linked to SPI Peripheral */
2518 if (HAL_DMA_Abort(hspi
->hdmatx
) != HAL_OK
)
2520 if (HAL_DMA_GetError(hspi
->hdmatx
) == HAL_DMA_ERROR_TIMEOUT
)
2522 hspi
->ErrorCode
= HAL_SPI_ERROR_ABORT
;
2528 /* Disable the SPI DMA Rx request if enabled */
2529 if (HAL_IS_BIT_SET(hspi
->Instance
->CFG1
, SPI_CFG1_RXDMAEN
))
2531 if (hspi
->hdmarx
!= NULL
)
2533 /* Abort the SPI DMA Rx Stream/Channel : use blocking DMA Abort API (no callback) */
2534 hspi
->hdmarx
->XferAbortCallback
= NULL
;
2536 /* Abort DMA Rx Handle linked to SPI Peripheral */
2537 if (HAL_DMA_Abort(hspi
->hdmarx
) != HAL_OK
)
2539 if (HAL_DMA_GetError(hspi
->hdmarx
) == HAL_DMA_ERROR_TIMEOUT
)
2541 hspi
->ErrorCode
= HAL_SPI_ERROR_ABORT
;
2547 /* Proceed with abort procedure */
2548 SPI_AbortTransfer(hspi
);
2550 /* Check error during Abort procedure */
2551 if (hspi
->ErrorCode
== HAL_SPI_ERROR_ABORT
)
2553 /* return HAL_Error in case of error during Abort procedure */
2554 errorcode
= HAL_ERROR
;
2558 /* Reset errorCode */
2559 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
2562 /* Process Unlocked */
2565 /* Restore hspi->state to ready */
2566 hspi
->State
= HAL_SPI_STATE_READY
;
2572 * @brief Abort ongoing transfer (Interrupt mode).
2573 * @param hspi SPI handle.
2574 * @note This procedure could be used for aborting any ongoing transfer (Tx and Rx),
2575 * started in Interrupt or DMA mode.
2576 * @note This procedure performs following operations :
2577 * + Disable SPI Interrupts (depending of transfer direction)
2578 * + Disable the DMA transfer in the peripheral register (if enabled)
2579 * + Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
2580 * + Set handle State to READY
2581 * + At abort completion, call user abort complete callback.
2582 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
2583 * considered as completed only when user abort complete callback is executed (not when exiting function).
2584 * @retval HAL status
2586 HAL_StatusTypeDef
HAL_SPI_Abort_IT(SPI_HandleTypeDef
*hspi
)
2588 HAL_StatusTypeDef errorcode
;
2589 __IO
uint32_t count
;
2590 uint32_t dma_tx_abort_done
= 1UL, dma_rx_abort_done
= 1UL;
2592 /* Set hspi->state to aborting to avoid any interaction */
2593 hspi
->State
= HAL_SPI_STATE_ABORT
;
2595 /* Initialized local variable */
2597 count
= SPI_DEFAULT_TIMEOUT
* (SystemCoreClock
/ 24UL / 1000UL);
2599 /* If master communication on going, make sure current frame is done before closing the connection */
2600 if (HAL_IS_BIT_SET(hspi
->Instance
->CR1
, SPI_CR1_CSTART
))
2602 SET_BIT(hspi
->Instance
->CR1
, SPI_CR1_CSUSP
);
2608 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_ABORT
);
2612 while (HAL_IS_BIT_SET(hspi
->Instance
->CR1
, SPI_CR1_CSTART
));
2615 /* If DMA Tx and/or DMA Rx Handles are associated to SPI Handle, DMA Abort complete callbacks should be initialized
2616 before any call to DMA Abort functions */
2618 if(hspi
->hdmatx
!= NULL
)
2620 if (HAL_IS_BIT_SET(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
))
2622 /* Set DMA Abort Complete callback if SPI DMA Tx request if enabled */
2623 hspi
->hdmatx
->XferAbortCallback
= SPI_DMATxAbortCallback
;
2625 dma_tx_abort_done
= 0UL;
2627 /* Abort DMA Tx Handle linked to SPI Peripheral */
2628 if (HAL_DMA_Abort_IT(hspi
->hdmatx
) != HAL_OK
)
2630 if (HAL_DMA_GetError(hspi
->hdmatx
) == HAL_DMA_ERROR_NO_XFER
)
2632 dma_tx_abort_done
= 1UL;
2633 hspi
->hdmatx
->XferAbortCallback
= NULL
;
2639 hspi
->hdmatx
->XferAbortCallback
= NULL
;
2643 if(hspi
->hdmarx
!= NULL
)
2645 if (HAL_IS_BIT_SET(hspi
->Instance
->CFG1
, SPI_CFG1_RXDMAEN
))
2647 /* Set DMA Abort Complete callback if SPI DMA Rx request if enabled */
2648 hspi
->hdmarx
->XferAbortCallback
= SPI_DMARxAbortCallback
;
2650 dma_rx_abort_done
= 0UL;
2652 /* Abort DMA Rx Handle linked to SPI Peripheral */
2653 if (HAL_DMA_Abort_IT(hspi
->hdmarx
) != HAL_OK
)
2655 if (HAL_DMA_GetError(hspi
->hdmarx
) == HAL_DMA_ERROR_NO_XFER
)
2657 dma_rx_abort_done
= 1UL;
2658 hspi
->hdmarx
->XferAbortCallback
= NULL
;
2664 hspi
->hdmarx
->XferAbortCallback
= NULL
;
2668 /* If no running DMA transfer, finish cleanup and call callbacks */
2669 if ((dma_tx_abort_done
== 1UL) && (dma_rx_abort_done
== 1UL))
2671 /* Proceed with abort procedure */
2672 SPI_AbortTransfer(hspi
);
2674 /* Check error during Abort procedure */
2675 if (hspi
->ErrorCode
== HAL_SPI_ERROR_ABORT
)
2677 /* return HAL_Error in case of error during Abort procedure */
2678 errorcode
= HAL_ERROR
;
2682 /* Reset errorCode */
2683 hspi
->ErrorCode
= HAL_SPI_ERROR_NONE
;
2686 /* Restore hspi->state to ready */
2687 hspi
->State
= HAL_SPI_STATE_READY
;
2689 /* Call user Abort complete callback */
2690 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
2691 hspi
->AbortCpltCallback(hspi
);
2693 HAL_SPI_AbortCpltCallback(hspi
);
2694 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
2701 * @brief Pause the DMA Transfer.
2702 * This API is not supported, it is maintained for backward compatibility.
2703 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2704 * the configuration information for the specified SPI module.
2707 HAL_StatusTypeDef
HAL_SPI_DMAPause(SPI_HandleTypeDef
*hspi
)
2709 /* Set error code to not supported */
2710 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_NOT_SUPPORTED
);
2716 * @brief Resume the DMA Transfer.
2717 * This API is not supported, it is maintained for backward compatibility.
2718 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2719 * the configuration information for the specified SPI module.
2722 HAL_StatusTypeDef
HAL_SPI_DMAResume(SPI_HandleTypeDef
*hspi
)
2724 /* Set error code to not supported */
2725 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_NOT_SUPPORTED
);
2731 * @brief Stop the DMA Transfer.
2732 * This API is not supported, it is maintained for backward compatibility.
2733 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2734 * the configuration information for the specified SPI module.
2737 HAL_StatusTypeDef
HAL_SPI_DMAStop(SPI_HandleTypeDef
*hspi
)
2739 /* Set error code to not supported */
2740 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_NOT_SUPPORTED
);
2746 * @brief Handle SPI interrupt request.
2747 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2748 * the configuration information for the specified SPI module.
2751 void HAL_SPI_IRQHandler(SPI_HandleTypeDef
*hspi
)
2753 uint32_t itsource
= hspi
->Instance
->IER
;
2754 uint32_t itflag
= hspi
->Instance
->SR
;
2755 uint32_t trigger
= itsource
& itflag
;
2756 uint32_t cfg1
= hspi
->Instance
->CFG1
;
2757 uint32_t handled
= 0UL;
2759 HAL_SPI_StateTypeDef State
= hspi
->State
;
2760 #if defined (__GNUC__)
2761 __IO
uint16_t *prxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->RXDR
));
2762 #endif /* __GNUC__ */
2765 /* SPI in mode Transmitter and Receiver ------------------------------------*/
2766 if (HAL_IS_BIT_CLR(trigger
, SPI_FLAG_OVR
) && HAL_IS_BIT_CLR(trigger
, SPI_FLAG_UDR
) && HAL_IS_BIT_SET(trigger
, SPI_FLAG_DXP
))
2773 /* SPI in mode Receiver ----------------------------------------------------*/
2774 if (HAL_IS_BIT_CLR(trigger
, SPI_FLAG_OVR
) && HAL_IS_BIT_SET(trigger
, SPI_FLAG_RXP
) && HAL_IS_BIT_CLR(trigger
, SPI_FLAG_DXP
))
2780 /* SPI in mode Transmitter -------------------------------------------------*/
2781 if (HAL_IS_BIT_CLR(trigger
, SPI_FLAG_UDR
) && HAL_IS_BIT_SET(trigger
, SPI_FLAG_TXP
) && HAL_IS_BIT_CLR(trigger
, SPI_FLAG_DXP
))
2787 #if defined(USE_SPI_RELOAD_TRANSFER)
2788 /* SPI Reload -------------------------------------------------*/
2789 if (HAL_IS_BIT_SET(trigger
, SPI_FLAG_TSERF
))
2791 hspi
->Reload
.Requested
= 0UL;
2792 __HAL_SPI_CLEAR_TSERFFLAG(hspi
);
2794 #endif /* USE_HSPI_RELOAD_TRANSFER */
2801 /* SPI End Of Transfer: DMA or IT based transfer */
2802 if (HAL_IS_BIT_SET(trigger
, SPI_FLAG_EOT
))
2804 /* Clear EOT/TXTF/SUSP flag */
2805 __HAL_SPI_CLEAR_EOTFLAG(hspi
);
2806 __HAL_SPI_CLEAR_TXTFFLAG(hspi
);
2807 __HAL_SPI_CLEAR_SUSPFLAG(hspi
);
2809 /* Disable EOT interrupt */
2810 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_EOT
);
2812 /* DMA Normal Mode */
2813 if (HAL_IS_BIT_CLR(cfg1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
) || // IT based transfer is done
2814 ((State
!= HAL_SPI_STATE_BUSY_RX
) && (hspi
->hdmatx
->Init
.Mode
== DMA_NORMAL
)) || // DMA is used in normal mode
2815 ((State
!= HAL_SPI_STATE_BUSY_TX
) && (hspi
->hdmarx
->Init
.Mode
== DMA_NORMAL
))) // DMA is used in normal mode
2817 /* For the IT based receive extra polling maybe required for last packet */
2818 if (HAL_IS_BIT_CLR(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
))
2820 /* Pooling remaining data */
2821 while (hspi
->RxXferCount
!= 0UL)
2823 /* Receive data in 32 Bit mode */
2824 if (hspi
->Init
.DataSize
> SPI_DATASIZE_16BIT
)
2826 *((uint32_t *)hspi
->pRxBuffPtr
) = *((__IO
uint32_t *)&hspi
->Instance
->RXDR
);
2827 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
2829 /* Receive data in 16 Bit mode */
2830 else if (hspi
->Init
.DataSize
> SPI_DATASIZE_8BIT
)
2832 #if defined (__GNUC__)
2833 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
2835 *((uint16_t *)hspi
->pRxBuffPtr
) = *((__IO
uint16_t *)&hspi
->Instance
->RXDR
);
2836 #endif /* __GNUC__ */
2837 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
2839 /* Receive data in 8 Bit mode */
2842 *((uint8_t *)hspi
->pRxBuffPtr
) = *((__IO
uint8_t *)&hspi
->Instance
->RXDR
);
2843 hspi
->pRxBuffPtr
+= sizeof(uint8_t);
2846 hspi
->RxXferCount
--;
2850 /* Call SPI Standard close procedure */
2851 SPI_CloseTransfer(hspi
);
2853 hspi
->State
= HAL_SPI_STATE_READY
;
2854 if (hspi
->ErrorCode
!= HAL_SPI_ERROR_NONE
)
2856 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
2857 hspi
->ErrorCallback(hspi
);
2859 HAL_SPI_ErrorCallback(hspi
);
2860 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
2865 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
2866 /* Call appropriate user callback */
2867 if (State
== HAL_SPI_STATE_BUSY_TX_RX
)
2869 hspi
->TxRxCpltCallback(hspi
);
2871 else if (State
== HAL_SPI_STATE_BUSY_RX
)
2873 hspi
->RxCpltCallback(hspi
);
2875 else if (State
== HAL_SPI_STATE_BUSY_TX
)
2877 hspi
->TxCpltCallback(hspi
);
2880 /* Call appropriate user callback */
2881 if (State
== HAL_SPI_STATE_BUSY_TX_RX
)
2883 HAL_SPI_TxRxCpltCallback(hspi
);
2885 else if (State
== HAL_SPI_STATE_BUSY_RX
)
2887 HAL_SPI_RxCpltCallback(hspi
);
2889 else if (State
== HAL_SPI_STATE_BUSY_TX
)
2891 HAL_SPI_TxCpltCallback(hspi
);
2895 /* end of the appropriate call */
2897 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
2902 if (HAL_IS_BIT_SET(itflag
, SPI_FLAG_SUSP
) && HAL_IS_BIT_SET(itsource
, SPI_FLAG_EOT
))
2904 /* Abort on going, clear SUSP flag to avoid infinite looping */
2905 __HAL_SPI_CLEAR_SUSPFLAG(hspi
);
2910 /* SPI in Error Treatment --------------------------------------------------*/
2911 if ((trigger
& (SPI_FLAG_MODF
| SPI_FLAG_OVR
| SPI_FLAG_FRE
| SPI_FLAG_UDR
)) != 0UL)
2913 /* SPI Overrun error interrupt occurred ----------------------------------*/
2914 if ((trigger
& SPI_FLAG_OVR
) != 0UL)
2916 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_OVR
);
2917 __HAL_SPI_CLEAR_OVRFLAG(hspi
);
2920 /* SPI Mode Fault error interrupt occurred -------------------------------*/
2921 if ((trigger
& SPI_FLAG_MODF
) != 0UL)
2923 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_MODF
);
2924 __HAL_SPI_CLEAR_MODFFLAG(hspi
);
2927 /* SPI Frame error interrupt occurred ------------------------------------*/
2928 if ((trigger
& SPI_FLAG_FRE
) != 0UL)
2930 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_FRE
);
2931 __HAL_SPI_CLEAR_FREFLAG(hspi
);
2934 /* SPI Underrun error interrupt occurred ------------------------------------*/
2935 if ((trigger
& SPI_FLAG_UDR
) != 0UL)
2937 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_UDR
);
2938 __HAL_SPI_CLEAR_UDRFLAG(hspi
);
2941 if (hspi
->ErrorCode
!= HAL_SPI_ERROR_NONE
)
2943 /* Disable SPI peripheral */
2944 __HAL_SPI_DISABLE(hspi
);
2946 /* Disable all interrupts */
2947 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_EOT
| SPI_IT_RXP
| SPI_IT_TXP
| SPI_IT_MODF
| SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_UDR
);
2949 /* Disable the SPI DMA requests if enabled */
2950 if (HAL_IS_BIT_SET(cfg1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
))
2952 /* Disable the SPI DMA requests */
2953 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
);
2955 /* Abort the SPI DMA Rx channel */
2956 if (hspi
->hdmarx
!= NULL
)
2958 /* Set the SPI DMA Abort callback :
2959 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2960 hspi
->hdmarx
->XferAbortCallback
= SPI_DMAAbortOnError
;
2961 if (HAL_OK
!= HAL_DMA_Abort_IT(hspi
->hdmarx
))
2963 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_ABORT
);
2966 /* Abort the SPI DMA Tx channel */
2967 if (hspi
->hdmatx
!= NULL
)
2969 /* Set the SPI DMA Abort callback :
2970 will lead to call HAL_SPI_ErrorCallback() at end of DMA abort procedure */
2971 hspi
->hdmatx
->XferAbortCallback
= SPI_DMAAbortOnError
;
2972 if (HAL_OK
!= HAL_DMA_Abort_IT(hspi
->hdmatx
))
2974 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_ABORT
);
2980 /* Restore hspi->State to Ready */
2981 hspi
->State
= HAL_SPI_STATE_READY
;
2983 /* Call user error callback */
2984 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
2985 hspi
->ErrorCallback(hspi
);
2987 HAL_SPI_ErrorCallback(hspi
);
2988 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
2996 * @brief Tx Transfer completed callback.
2997 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
2998 * the configuration information for SPI module.
3001 __weak
void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef
*hspi
)
3003 /* Prevent unused argument(s) compilation warning */
3006 /* NOTE : This function should not be modified, when the callback is needed,
3007 the HAL_SPI_TxCpltCallback should be implemented in the user file
3012 * @brief Rx Transfer completed callback.
3013 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3014 * the configuration information for SPI module.
3017 __weak
void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef
*hspi
)
3019 /* Prevent unused argument(s) compilation warning */
3022 /* NOTE : This function should not be modified, when the callback is needed,
3023 the HAL_SPI_RxCpltCallback should be implemented in the user file
3028 * @brief Tx and Rx Transfer completed callback.
3029 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3030 * the configuration information for SPI module.
3033 __weak
void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef
*hspi
)
3035 /* Prevent unused argument(s) compilation warning */
3038 /* NOTE : This function should not be modified, when the callback is needed,
3039 the HAL_SPI_TxRxCpltCallback should be implemented in the user file
3044 * @brief Tx Half Transfer completed callback.
3045 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3046 * the configuration information for SPI module.
3049 __weak
void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef
*hspi
)
3051 /* Prevent unused argument(s) compilation warning */
3054 /* NOTE : This function should not be modified, when the callback is needed,
3055 the HAL_SPI_TxHalfCpltCallback should be implemented in the user file
3060 * @brief Rx Half Transfer completed callback.
3061 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3062 * the configuration information for SPI module.
3065 __weak
void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef
*hspi
)
3067 /* Prevent unused argument(s) compilation warning */
3070 /* NOTE : This function should not be modified, when the callback is needed,
3071 the HAL_SPI_RxHalfCpltCallback() should be implemented in the user file
3076 * @brief Tx and Rx Half Transfer callback.
3077 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3078 * the configuration information for SPI module.
3081 __weak
void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef
*hspi
)
3083 /* Prevent unused argument(s) compilation warning */
3086 /* NOTE : This function should not be modified, when the callback is needed,
3087 the HAL_SPI_TxRxHalfCpltCallback() should be implemented in the user file
3092 * @brief SPI error callback.
3093 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3094 * the configuration information for SPI module.
3097 __weak
void HAL_SPI_ErrorCallback(SPI_HandleTypeDef
*hspi
)
3099 /* Prevent unused argument(s) compilation warning */
3102 /* NOTE : This function should not be modified, when the callback is needed,
3103 the HAL_SPI_ErrorCallback should be implemented in the user file
3105 /* NOTE : The ErrorCode parameter in the hspi handle is updated by the SPI processes
3106 and user can use HAL_SPI_GetError() API to check the latest error occurred
3111 * @brief SPI Abort Complete callback.
3112 * @param hspi SPI handle.
3115 __weak
void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef
*hspi
)
3117 /* Prevent unused argument(s) compilation warning */
3120 /* NOTE : This function should not be modified, when the callback is needed,
3121 the HAL_SPI_AbortCpltCallback can be implemented in the user file.
3129 /** @defgroup SPI_Exported_Functions_Group3 Peripheral State and Errors functions
3130 * @brief SPI control functions
3133 ===============================================================================
3134 ##### Peripheral State and Errors functions #####
3135 ===============================================================================
3137 This subsection provides a set of functions allowing to control the SPI.
3138 (+) HAL_SPI_GetState() API can be helpful to check in run-time the state of the SPI peripheral
3139 (+) HAL_SPI_GetError() check in run-time Errors occurring during communication
3145 * @brief Return the SPI handle state.
3146 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3147 * the configuration information for SPI module.
3150 HAL_SPI_StateTypeDef
HAL_SPI_GetState(SPI_HandleTypeDef
*hspi
)
3152 /* Return SPI handle state */
3157 * @brief Return the SPI error code.
3158 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3159 * the configuration information for SPI module.
3160 * @retval SPI error code in bitmap format
3162 uint32_t HAL_SPI_GetError(SPI_HandleTypeDef
*hspi
)
3164 /* Return SPI ErrorCode */
3165 return hspi
->ErrorCode
;
3176 /** @addtogroup SPI_Private_Functions
3177 * @brief Private functions
3182 * @brief DMA SPI transmit process complete callback.
3183 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3184 * the configuration information for the specified DMA module.
3187 static void SPI_DMATransmitCplt(DMA_HandleTypeDef
*hdma
)
3189 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3191 if (hspi
->State
!= HAL_SPI_STATE_ABORT
)
3193 if (hspi
->hdmatx
->Init
.Mode
== DMA_CIRCULAR
)
3195 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3196 hspi
->TxCpltCallback(hspi
);
3198 HAL_SPI_TxCpltCallback(hspi
);
3199 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3203 /* Enable EOT interrupt */
3204 __HAL_SPI_ENABLE_IT(hspi
, SPI_IT_EOT
);
3210 * @brief DMA SPI receive process complete callback.
3211 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3212 * the configuration information for the specified DMA module.
3215 static void SPI_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
)
3217 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3219 if (hspi
->State
!= HAL_SPI_STATE_ABORT
)
3221 if (hspi
->hdmarx
->Init
.Mode
== DMA_CIRCULAR
)
3223 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3224 hspi
->RxCpltCallback(hspi
);
3226 HAL_SPI_RxCpltCallback(hspi
);
3227 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3231 /* Enable EOT interrupt */
3232 __HAL_SPI_ENABLE_IT(hspi
, SPI_IT_EOT
);
3238 * @brief DMA SPI transmit receive process complete callback.
3239 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3240 * the configuration information for the specified DMA module.
3243 static void SPI_DMATransmitReceiveCplt(DMA_HandleTypeDef
*hdma
)
3245 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3247 if (hspi
->State
!= HAL_SPI_STATE_ABORT
)
3249 if (hspi
->hdmatx
->Init
.Mode
== DMA_CIRCULAR
)
3251 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3252 hspi
->TxRxCpltCallback(hspi
);
3254 HAL_SPI_TxRxCpltCallback(hspi
);
3255 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3259 /* Enable EOT interrupt */
3260 __HAL_SPI_ENABLE_IT(hspi
, SPI_IT_EOT
);
3266 * @brief DMA SPI half transmit process complete callback.
3267 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3268 * the configuration information for the specified DMA module.
3271 static void SPI_DMAHalfTransmitCplt(DMA_HandleTypeDef
*hdma
)
3273 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3275 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3276 hspi
->TxHalfCpltCallback(hspi
);
3278 HAL_SPI_TxHalfCpltCallback(hspi
);
3279 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3283 * @brief DMA SPI half receive process complete callback
3284 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3285 * the configuration information for the specified DMA module.
3288 static void SPI_DMAHalfReceiveCplt(DMA_HandleTypeDef
*hdma
)
3290 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3292 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3293 hspi
->RxHalfCpltCallback(hspi
);
3295 HAL_SPI_RxHalfCpltCallback(hspi
);
3296 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3300 * @brief DMA SPI half transmit receive process complete callback.
3301 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3302 * the configuration information for the specified DMA module.
3305 static void SPI_DMAHalfTransmitReceiveCplt(DMA_HandleTypeDef
*hdma
)
3307 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3309 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3310 hspi
->TxRxHalfCpltCallback(hspi
);
3312 HAL_SPI_TxRxHalfCpltCallback(hspi
);
3313 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3317 * @brief DMA SPI communication error callback.
3318 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
3319 * the configuration information for the specified DMA module.
3322 static void SPI_DMAError(DMA_HandleTypeDef
*hdma
)
3324 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3326 /* if DMA error is FIFO error ignore it */
3327 if (HAL_DMA_GetError(hdma
) != HAL_DMA_ERROR_FE
)
3329 /* Call SPI standard close procedure */
3330 SPI_CloseTransfer(hspi
);
3332 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_DMA
);
3333 hspi
->State
= HAL_SPI_STATE_READY
;
3334 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3335 hspi
->ErrorCallback(hspi
);
3337 HAL_SPI_ErrorCallback(hspi
);
3338 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3343 * @brief DMA SPI communication abort callback, when initiated by HAL services on Error
3344 * (To be called at end of DMA Abort procedure following error occurrence).
3345 * @param hdma DMA handle.
3348 static void SPI_DMAAbortOnError(DMA_HandleTypeDef
*hdma
)
3350 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3351 hspi
->RxXferCount
= (uint16_t) 0UL;
3352 hspi
->TxXferCount
= (uint16_t) 0UL;
3354 /* Restore hspi->State to Ready */
3355 hspi
->State
= HAL_SPI_STATE_READY
;
3357 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3358 hspi
->ErrorCallback(hspi
);
3360 HAL_SPI_ErrorCallback(hspi
);
3361 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3365 * @brief DMA SPI Tx communication abort callback, when initiated by user
3366 * (To be called at end of DMA Tx Abort procedure following user abort request).
3367 * @note When this callback is executed, User Abort complete call back is called only if no
3368 * Abort still ongoing for Rx DMA Handle.
3369 * @param hdma DMA handle.
3372 static void SPI_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
)
3374 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3376 hspi
->hdmatx
->XferAbortCallback
= NULL
;
3378 /* Check if an Abort process is still ongoing */
3379 if (hspi
->hdmarx
!= NULL
)
3381 if (hspi
->hdmarx
->XferAbortCallback
!= NULL
)
3387 /* Call the Abort procedure */
3388 SPI_AbortTransfer(hspi
);
3390 /* Restore hspi->State to Ready */
3391 hspi
->State
= HAL_SPI_STATE_READY
;
3393 /* Call user Abort complete callback */
3394 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3395 hspi
->AbortCpltCallback(hspi
);
3397 HAL_SPI_AbortCpltCallback(hspi
);
3398 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3402 * @brief DMA SPI Rx communication abort callback, when initiated by user
3403 * (To be called at end of DMA Rx Abort procedure following user abort request).
3404 * @note When this callback is executed, User Abort complete call back is called only if no
3405 * Abort still ongoing for Tx DMA Handle.
3406 * @param hdma DMA handle.
3409 static void SPI_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
)
3411 SPI_HandleTypeDef
*hspi
= (SPI_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
3413 hspi
->hdmarx
->XferAbortCallback
= NULL
;
3415 /* Check if an Abort process is still ongoing */
3416 if (hspi
->hdmatx
!= NULL
)
3418 if (hspi
->hdmatx
->XferAbortCallback
!= NULL
)
3424 /* Call the Abort procedure */
3425 SPI_AbortTransfer(hspi
);
3427 /* Restore hspi->State to Ready */
3428 hspi
->State
= HAL_SPI_STATE_READY
;
3430 /* Call user Abort complete callback */
3431 #if (USE_HAL_SPI_REGISTER_CALLBACKS == 1UL)
3432 hspi
->AbortCpltCallback(hspi
);
3434 HAL_SPI_AbortCpltCallback(hspi
);
3435 #endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
3439 * @brief Manage the receive 8-bit in Interrupt context.
3440 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3441 * the configuration information for SPI module.
3444 static void SPI_RxISR_8BIT(SPI_HandleTypeDef
*hspi
)
3446 /* Receive data in 8 Bit mode */
3447 *((uint8_t *)hspi
->pRxBuffPtr
) = (*(__IO
uint8_t *)&hspi
->Instance
->RXDR
);
3448 hspi
->pRxBuffPtr
+= sizeof(uint8_t);
3449 hspi
->RxXferCount
--;
3451 /* Disable IT if no more data excepted */
3452 if (hspi
->RxXferCount
== 0UL)
3454 #if defined(USE_SPI_RELOAD_TRANSFER)
3455 /* Check if there is any request to reload */
3456 if (hspi
->Reload
.Requested
== 1UL)
3458 hspi
->RxXferSize
= hspi
->Reload
.RxXferSize
;
3459 hspi
->RxXferCount
= hspi
->Reload
.RxXferSize
;
3460 hspi
->pRxBuffPtr
= hspi
->Reload
.pRxBuffPtr
;
3464 /* Disable RXP interrupts */
3465 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3468 /* Disable RXP interrupts */
3469 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3470 #endif /* USE_HSPI_RELOAD_TRANSFER */
3476 * @brief Manage the 16-bit receive in Interrupt context.
3477 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3478 * the configuration information for SPI module.
3481 static void SPI_RxISR_16BIT(SPI_HandleTypeDef
*hspi
)
3483 /* Receive data in 16 Bit mode */
3484 #if defined (__GNUC__)
3485 __IO
uint16_t *prxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->RXDR
));
3487 *((uint16_t *)hspi
->pRxBuffPtr
) = *prxdr_16bits
;
3489 *((uint16_t *)hspi
->pRxBuffPtr
) = (*(__IO
uint16_t *)&hspi
->Instance
->RXDR
);
3490 #endif /* __GNUC__ */
3491 hspi
->pRxBuffPtr
+= sizeof(uint16_t);
3492 hspi
->RxXferCount
--;
3494 /* Disable IT if no more data excepted */
3495 if (hspi
->RxXferCount
== 0UL)
3497 #if defined(USE_SPI_RELOAD_TRANSFER)
3498 /* Check if there is any request to reload */
3499 if (hspi
->Reload
.Requested
== 1UL)
3501 hspi
->RxXferSize
= hspi
->Reload
.RxXferSize
;
3502 hspi
->RxXferCount
= hspi
->Reload
.RxXferSize
;
3503 hspi
->pRxBuffPtr
= hspi
->Reload
.pRxBuffPtr
;
3507 /* Disable RXP interrupts */
3508 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3511 /* Disable RXP interrupts */
3512 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3513 #endif /* USE_HSPI_RELOAD_TRANSFER */
3519 * @brief Manage the 32-bit receive in Interrupt context.
3520 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3521 * the configuration information for SPI module.
3524 static void SPI_RxISR_32BIT(SPI_HandleTypeDef
*hspi
)
3526 /* Receive data in 32 Bit mode */
3527 *((uint32_t *)hspi
->pRxBuffPtr
) = (*(__IO
uint32_t *)&hspi
->Instance
->RXDR
);
3528 hspi
->pRxBuffPtr
+= sizeof(uint32_t);
3529 hspi
->RxXferCount
--;
3531 /* Disable IT if no more data excepted */
3532 if (hspi
->RxXferCount
== 0UL)
3534 #if defined(USE_SPI_RELOAD_TRANSFER)
3535 /* Check if there is any request to reload */
3536 if (hspi
->Reload
.Requested
== 1UL)
3538 hspi
->RxXferSize
= hspi
->Reload
.RxXferSize
;
3539 hspi
->RxXferCount
= hspi
->Reload
.RxXferSize
;
3540 hspi
->pRxBuffPtr
= hspi
->Reload
.pRxBuffPtr
;
3544 /* Disable RXP interrupts */
3545 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3548 /* Disable RXP interrupts */
3549 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_RXP
);
3550 #endif /* USE_HSPI_RELOAD_TRANSFER */
3556 * @brief Handle the data 8-bit transmit in Interrupt mode.
3557 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3558 * the configuration information for SPI module.
3561 static void SPI_TxISR_8BIT(SPI_HandleTypeDef
*hspi
)
3563 /* Transmit data in 8 Bit mode */
3564 *(__IO
uint8_t *)&hspi
->Instance
->TXDR
= *((uint8_t *)hspi
->pTxBuffPtr
);
3565 hspi
->pTxBuffPtr
+= sizeof(uint8_t);
3566 hspi
->TxXferCount
--;
3568 /* Disable IT if no more data excepted */
3569 if (hspi
->TxXferCount
== 0UL)
3571 #if defined(USE_SPI_RELOAD_TRANSFER)
3572 /* Check if there is any request to reload */
3573 if (hspi
->Reload
.Requested
== 1UL)
3575 hspi
->TxXferSize
= hspi
->Reload
.TxXferSize
;
3576 hspi
->TxXferCount
= hspi
->Reload
.TxXferSize
;
3577 hspi
->pTxBuffPtr
= hspi
->Reload
.pTxBuffPtr
;
3581 /* Disable TXP interrupts */
3582 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3585 /* Disable TXP interrupts */
3586 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3587 #endif /* USE_HSPI_RELOAD_TRANSFER */
3592 * @brief Handle the data 16-bit transmit in Interrupt mode.
3593 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3594 * the configuration information for SPI module.
3597 static void SPI_TxISR_16BIT(SPI_HandleTypeDef
*hspi
)
3599 /* Transmit data in 16 Bit mode */
3600 #if defined (__GNUC__)
3601 __IO
uint16_t *ptxdr_16bits
= (__IO
uint16_t *)(&(hspi
->Instance
->TXDR
));
3603 *ptxdr_16bits
= *((uint16_t *)hspi
->pTxBuffPtr
);
3605 *((__IO
uint16_t *)&hspi
->Instance
->TXDR
) = *((uint16_t *)hspi
->pTxBuffPtr
);
3606 #endif /* __GNUC__ */
3607 hspi
->pTxBuffPtr
+= sizeof(uint16_t);
3608 hspi
->TxXferCount
--;
3610 /* Disable IT if no more data excepted */
3611 if (hspi
->TxXferCount
== 0UL)
3613 #if defined(USE_SPI_RELOAD_TRANSFER)
3614 /* Check if there is any request to reload */
3615 if (hspi
->Reload
.Requested
== 1UL)
3617 hspi
->TxXferSize
= hspi
->Reload
.TxXferSize
;
3618 hspi
->TxXferCount
= hspi
->Reload
.TxXferSize
;
3619 hspi
->pTxBuffPtr
= hspi
->Reload
.pTxBuffPtr
;
3623 /* Disable TXP interrupts */
3624 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3627 /* Disable TXP interrupts */
3628 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3629 #endif /* USE_HSPI_RELOAD_TRANSFER */
3634 * @brief Handle the data 32-bit transmit in Interrupt mode.
3635 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3636 * the configuration information for SPI module.
3639 static void SPI_TxISR_32BIT(SPI_HandleTypeDef
*hspi
)
3641 /* Transmit data in 32 Bit mode */
3642 *((__IO
uint32_t *)&hspi
->Instance
->TXDR
) = *((uint32_t *)hspi
->pTxBuffPtr
);
3643 hspi
->pTxBuffPtr
+= sizeof(uint32_t);
3644 hspi
->TxXferCount
--;
3646 /* Disable IT if no more data excepted */
3647 if (hspi
->TxXferCount
== 0UL)
3649 #if defined(USE_SPI_RELOAD_TRANSFER)
3650 /* Check if there is any request to reload */
3651 if (hspi
->Reload
.Requested
== 1UL)
3653 hspi
->TxXferSize
= hspi
->Reload
.TxXferSize
;
3654 hspi
->TxXferCount
= hspi
->Reload
.TxXferSize
;
3655 hspi
->pTxBuffPtr
= hspi
->Reload
.pTxBuffPtr
;
3659 /* Disable TXP interrupts */
3660 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3663 /* Disable TXP interrupts */
3664 __HAL_SPI_DISABLE_IT(hspi
, SPI_IT_TXP
);
3665 #endif /* USE_HSPI_RELOAD_TRANSFER */
3670 * @brief Abort Transfer and clear flags.
3671 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3672 * the configuration information for SPI module.
3675 static void SPI_AbortTransfer(SPI_HandleTypeDef
*hspi
)
3677 /* Disable SPI peripheral */
3678 __HAL_SPI_DISABLE(hspi
);
3681 __HAL_SPI_DISABLE_IT(hspi
, (SPI_IT_EOT
| SPI_IT_TXP
| SPI_IT_RXP
| SPI_IT_DXP
| SPI_IT_UDR
| SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_MODF
));
3683 /* Clear the Status flags in the SR register */
3684 __HAL_SPI_CLEAR_EOTFLAG(hspi
);
3685 __HAL_SPI_CLEAR_TXTFFLAG(hspi
);
3687 /* Disable Tx DMA Request */
3688 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
);
3690 /* Clear the Error flags in the SR register */
3691 __HAL_SPI_CLEAR_OVRFLAG(hspi
);
3692 __HAL_SPI_CLEAR_UDRFLAG(hspi
);
3693 __HAL_SPI_CLEAR_FREFLAG(hspi
);
3694 __HAL_SPI_CLEAR_MODFFLAG(hspi
);
3695 __HAL_SPI_CLEAR_SUSPFLAG(hspi
);
3697 #if (USE_SPI_CRC != 0U)
3698 __HAL_SPI_CLEAR_CRCERRFLAG(hspi
);
3699 #endif /* USE_SPI_CRC */
3701 hspi
->TxXferCount
= (uint16_t)0UL;
3702 hspi
->RxXferCount
= (uint16_t)0UL;
3707 * @brief Close Transfer and clear flags.
3708 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3709 * the configuration information for SPI module.
3710 * @retval HAL_ERROR: if any error detected
3711 * HAL_OK: if nothing detected
3713 static void SPI_CloseTransfer(SPI_HandleTypeDef
*hspi
)
3715 uint32_t itflag
= hspi
->Instance
->SR
;
3717 __HAL_SPI_CLEAR_EOTFLAG(hspi
);
3718 __HAL_SPI_CLEAR_TXTFFLAG(hspi
);
3720 /* Disable SPI peripheral */
3721 __HAL_SPI_DISABLE(hspi
);
3724 __HAL_SPI_DISABLE_IT(hspi
, (SPI_IT_EOT
| SPI_IT_TXP
| SPI_IT_RXP
| SPI_IT_DXP
| SPI_IT_UDR
| SPI_IT_OVR
| SPI_IT_FRE
| SPI_IT_MODF
));
3726 /* Disable Tx DMA Request */
3727 CLEAR_BIT(hspi
->Instance
->CFG1
, SPI_CFG1_TXDMAEN
| SPI_CFG1_RXDMAEN
);
3729 /* Report UnderRun error for non RX Only communication */
3730 if (hspi
->State
!= HAL_SPI_STATE_BUSY_RX
)
3732 if ((itflag
& SPI_FLAG_UDR
) != 0UL)
3734 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_UDR
);
3735 __HAL_SPI_CLEAR_UDRFLAG(hspi
);
3739 /* Report OverRun error for non TX Only communication */
3740 if (hspi
->State
!= HAL_SPI_STATE_BUSY_TX
)
3742 if ((itflag
& SPI_FLAG_OVR
) != 0UL)
3744 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_OVR
);
3745 __HAL_SPI_CLEAR_OVRFLAG(hspi
);
3748 #if (USE_SPI_CRC != 0UL)
3749 /* Check if CRC error occurred */
3750 if (hspi
->Init
.CRCCalculation
== SPI_CRCCALCULATION_ENABLE
)
3752 if ((itflag
& SPI_FLAG_CRCERR
) != 0UL)
3754 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_CRC
);
3755 __HAL_SPI_CLEAR_CRCERRFLAG(hspi
);
3758 #endif /* USE_SPI_CRC */
3761 /* SPI Mode Fault error interrupt occurred -------------------------------*/
3762 if ((itflag
& SPI_FLAG_MODF
) != 0UL)
3764 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_MODF
);
3765 __HAL_SPI_CLEAR_MODFFLAG(hspi
);
3768 /* SPI Frame error interrupt occurred ------------------------------------*/
3769 if ((itflag
& SPI_FLAG_FRE
) != 0UL)
3771 SET_BIT(hspi
->ErrorCode
, HAL_SPI_ERROR_FRE
);
3772 __HAL_SPI_CLEAR_FREFLAG(hspi
);
3775 hspi
->TxXferCount
= (uint16_t)0UL;
3776 hspi
->RxXferCount
= (uint16_t)0UL;
3780 * @brief Handle SPI Communication Timeout.
3781 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3782 * the configuration information for SPI module.
3783 * @param Flag: SPI flag to check
3784 * @param Status: flag state to check
3785 * @param Timeout: Timeout duration
3786 * @param Tickstart: Tick start value
3787 * @retval HAL status
3789 static HAL_StatusTypeDef
SPI_WaitOnFlagUntilTimeout(SPI_HandleTypeDef
*hspi
, uint32_t Flag
, FlagStatus Status
,
3790 uint32_t Tickstart
, uint32_t Timeout
)
3792 /* Wait until flag is set */
3793 while ((__HAL_SPI_GET_FLAG(hspi
, Flag
) ? SET
: RESET
) == Status
)
3795 /* Check for the Timeout */
3796 if ((((HAL_GetTick() - Tickstart
) >= Timeout
) && (Timeout
!= HAL_MAX_DELAY
)) || (Timeout
== 0U))
3805 * @brief Compute configured packet size from fifo perspective.
3806 * @param hspi: pointer to a SPI_HandleTypeDef structure that contains
3807 * the configuration information for SPI module.
3808 * @retval Packet size occupied in the fifo
3810 static uint32_t SPI_GetPacketSize(SPI_HandleTypeDef
*hspi
)
3812 uint32_t fifo_threashold
= (hspi
->Init
.FifoThreshold
>> SPI_CFG1_FTHLV_Pos
) + 1UL;
3813 uint32_t data_size
= (hspi
->Init
.DataSize
>> SPI_CFG1_DSIZE_Pos
) + 1UL;
3815 /* Convert data size to Byte */
3816 data_size
= (data_size
+ 7UL) / 8UL;
3818 return data_size
* fifo_threashold
;
3826 #endif /* HAL_SPI_MODULE_ENABLED */
3836 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/