F1 and F3 HAL / LL libraries
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_smartcard.c
blobc5ccfebb860fc30f5c0bf05d9148e79de18513f8
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_smartcard.c
4 * @author MCD Application Team
5 * @brief SMARTCARD HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the SMARTCARD peripheral:
8 * + Initialization and de-initialization functions
9 * + IO operation functions
10 * + Peripheral Control functions
11 * + Peripheral State and Error functions
13 @verbatim
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
17 [..]
18 The SMARTCARD HAL driver can be used as follows:
20 (#) Declare a SMARTCARD_HandleTypeDef handle structure (eg. SMARTCARD_HandleTypeDef hsmartcard).
21 (#) Associate a USART to the SMARTCARD handle hsmartcard.
22 (#) Initialize the SMARTCARD low level resources by implementing the HAL_SMARTCARD_MspInit() API:
23 (++) Enable the USARTx interface clock.
24 (++) USART pins configuration:
25 (+++) Enable the clock for the USART GPIOs.
26 (+++) Configure the USART pins (TX as alternate function pull-up, RX as alternate function Input).
27 (++) NVIC configuration if you need to use interrupt process (HAL_SMARTCARD_Transmit_IT()
28 and HAL_SMARTCARD_Receive_IT() APIs):
29 (+++) Configure the USARTx interrupt priority.
30 (+++) Enable the NVIC USART IRQ handle.
31 (++) DMA Configuration if you need to use DMA process (HAL_SMARTCARD_Transmit_DMA()
32 and HAL_SMARTCARD_Receive_DMA() APIs):
33 (+++) Declare a DMA handle structure for the Tx/Rx channel.
34 (+++) Enable the DMAx interface clock.
35 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
36 (+++) Configure the DMA Tx/Rx channel.
37 (+++) Associate the initialized DMA handle to the SMARTCARD DMA Tx/Rx handle.
38 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx channel.
40 (#) Program the Baud Rate, Parity, Mode(Receiver/Transmitter), clock enabling/disabling and accordingly,
41 the clock parameters (parity, phase, last bit), prescaler value, guard time and NACK on transmission
42 error enabling or disabling in the hsmartcard handle Init structure.
44 (#) If required, program SMARTCARD advanced features (TX/RX pins swap, TimeOut, auto-retry counter,...)
45 in the hsmartcard handle AdvancedInit structure.
47 (#) Initialize the SMARTCARD registers by calling the HAL_SMARTCARD_Init() API:
48 (++) This API configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc)
49 by calling the customized HAL_SMARTCARD_MspInit() API.
50 [..]
51 (@) The specific SMARTCARD interrupts (Transmission complete interrupt,
52 RXNE interrupt and Error Interrupts) will be managed using the macros
53 __HAL_SMARTCARD_ENABLE_IT() and __HAL_SMARTCARD_DISABLE_IT() inside the transmit and receive process.
55 [..]
56 [..] Three operation modes are available within this driver :
58 *** Polling mode IO operation ***
59 =================================
60 [..]
61 (+) Send an amount of data in blocking mode using HAL_SMARTCARD_Transmit()
62 (+) Receive an amount of data in blocking mode using HAL_SMARTCARD_Receive()
64 *** Interrupt mode IO operation ***
65 ===================================
66 [..]
67 (+) Send an amount of data in non-blocking mode using HAL_SMARTCARD_Transmit_IT()
68 (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback() is executed and user can
69 add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback()
70 (+) Receive an amount of data in non-blocking mode using HAL_SMARTCARD_Receive_IT()
71 (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback() is executed and user can
72 add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback()
73 (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can
74 add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback()
76 *** DMA mode IO operation ***
77 ==============================
78 [..]
79 (+) Send an amount of data in non-blocking mode (DMA) using HAL_SMARTCARD_Transmit_DMA()
80 (+) At transmission end of transfer HAL_SMARTCARD_TxCpltCallback() is executed and user can
81 add his own code by customization of function pointer HAL_SMARTCARD_TxCpltCallback()
82 (+) Receive an amount of data in non-blocking mode (DMA) using HAL_SMARTCARD_Receive_DMA()
83 (+) At reception end of transfer HAL_SMARTCARD_RxCpltCallback() is executed and user can
84 add his own code by customization of function pointer HAL_SMARTCARD_RxCpltCallback()
85 (+) In case of transfer Error, HAL_SMARTCARD_ErrorCallback() function is executed and user can
86 add his own code by customization of function pointer HAL_SMARTCARD_ErrorCallback()
88 *** SMARTCARD HAL driver macros list ***
89 ========================================
90 [..]
91 Below the list of most used macros in SMARTCARD HAL driver.
93 (+) __HAL_SMARTCARD_GET_FLAG : Check whether or not the specified SMARTCARD flag is set
94 (+) __HAL_SMARTCARD_CLEAR_FLAG : Clear the specified SMARTCARD pending flag
95 (+) __HAL_SMARTCARD_ENABLE_IT: Enable the specified SMARTCARD interrupt
96 (+) __HAL_SMARTCARD_DISABLE_IT: Disable the specified SMARTCARD interrupt
97 (+) __HAL_SMARTCARD_GET_IT_SOURCE: Check whether or not the specified SMARTCARD interrupt is enabled
99 [..]
100 (@) You can refer to the SMARTCARD HAL driver header file for more useful macros
102 @endverbatim
103 ******************************************************************************
104 * @attention
106 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
108 * Redistribution and use in source and binary forms, with or without modification,
109 * are permitted provided that the following conditions are met:
110 * 1. Redistributions of source code must retain the above copyright notice,
111 * this list of conditions and the following disclaimer.
112 * 2. Redistributions in binary form must reproduce the above copyright notice,
113 * this list of conditions and the following disclaimer in the documentation
114 * and/or other materials provided with the distribution.
115 * 3. Neither the name of STMicroelectronics nor the names of its contributors
116 * may be used to endorse or promote products derived from this software
117 * without specific prior written permission.
119 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
120 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
121 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
122 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
123 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
124 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
125 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
126 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
127 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
128 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
130 ******************************************************************************
133 /* Includes ------------------------------------------------------------------*/
134 #include "stm32f3xx_hal.h"
136 /** @addtogroup STM32F3xx_HAL_Driver
137 * @{
140 /** @defgroup SMARTCARD SMARTCARD
141 * @brief SMARTCARD HAL module driver
142 * @{
145 #ifdef HAL_SMARTCARD_MODULE_ENABLED
147 /* Private typedef -----------------------------------------------------------*/
148 /* Private define ------------------------------------------------------------*/
149 /** @defgroup SMARTCARD_Private_Constants SMARTCARD Private Constants
150 * @{
152 #define SMARTCARD_TEACK_REACK_TIMEOUT 1000 /*!< SMARTCARD TX or RX enable acknowledge time-out value */
154 #define USART_CR1_FIELDS ((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | \
155 USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8)) /*!< USART CR1 fields of parameters set by SMARTCARD_SetConfig API */
156 #define USART_CR2_CLK_FIELDS ((uint32_t)(USART_CR2_CLKEN|USART_CR2_CPOL|USART_CR2_CPHA|USART_CR2_LBCL)) /*!< SMARTCARD clock-related USART CR2 fields of parameters */
157 #define USART_CR2_FIELDS ((uint32_t)(USART_CR2_RTOEN|USART_CR2_CLK_FIELDS|USART_CR2_STOP)) /*!< USART CR2 fields of parameters set by SMARTCARD_SetConfig API */
158 #define USART_CR3_FIELDS ((uint32_t)(USART_CR3_ONEBIT|USART_CR3_NACK|USART_CR3_SCARCNT)) /*!< USART CR3 fields of parameters set by SMARTCARD_SetConfig API */
160 * @}
163 /* Private macros ------------------------------------------------------------*/
164 /* Private variables ---------------------------------------------------------*/
165 /* Private function prototypes -----------------------------------------------*/
166 /** @addtogroup SMARTCARD_Private_Functions
167 * @{
169 static HAL_StatusTypeDef SMARTCARD_SetConfig(SMARTCARD_HandleTypeDef *hsmartcard);
170 static void SMARTCARD_AdvFeatureConfig(SMARTCARD_HandleTypeDef *hsmartcard);
171 static HAL_StatusTypeDef SMARTCARD_CheckIdleState(SMARTCARD_HandleTypeDef *hsmartcard);
172 static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsmartcard, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout);
173 static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsmartcard);
174 static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsmartcard);
175 static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma);
176 static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
177 static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma);
178 static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma);
179 static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
180 static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
181 static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma);
182 static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma);
183 static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsmartcard);
184 static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsmartcard);
185 static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsmartcard);
187 * @}
190 /* Exported functions --------------------------------------------------------*/
192 /** @defgroup SMARTCARD_Exported_Functions SMARTCARD Exported Functions
193 * @{
196 /** @defgroup SMARTCARD_Exported_Functions_Group1 Initialization and de-initialization functions
197 * @brief Initialization and Configuration functions
199 @verbatim
200 ==============================================================================
201 ##### Initialization and Configuration functions #####
202 ==============================================================================
203 [..]
204 This subsection provides a set of functions allowing to initialize the USARTx
205 associated to the SmartCard.
206 [..]
207 The Smartcard interface is designed to support asynchronous protocol Smartcards as
208 defined in the ISO 7816-3 standard.
209 [..]
210 The USART can provide a clock to the smartcard through the SCLK output.
211 In smartcard mode, SCLK is not associated to the communication but is simply derived
212 from the internal peripheral input clock through a 5-bit prescaler.
213 [..]
214 (+) These parameters can be configured:
215 (++) Baud Rate
216 (++) Parity: should be enabled
217 (++) Receiver/transmitter modes
218 (++) Synchronous mode (and if enabled, phase, polarity and last bit parameters)
219 (++) Prescaler value
220 (++) Guard bit time
221 (++) NACK enabling or disabling on transmission error
223 (+) The following advanced features can be configured as well:
224 (++) TX and/or RX pin level inversion
225 (++) data logical level inversion
226 (++) RX and TX pins swap
227 (++) RX overrun detection disabling
228 (++) DMA disabling on RX error
229 (++) MSB first on communication line
230 (++) Time out enabling (and if activated, timeout value)
231 (++) Block length
232 (++) Auto-retry counter
233 [..]
234 The HAL_SMARTCARD_Init() API follows the USART synchronous configuration procedures
235 (details for the procedures are available in reference manual).
237 @endverbatim
238 * @{
242 Additional Table:
243 Frame Length is fixed to 8 bits plus parity:
244 SMARTCARD frame format is given in the following table:
245 +---------------------------------------------------------------+
246 | M1M0 bits | PCE bit | SMARTCARD frame |
247 |-----------------------|---------------------------------------|
248 | 01 | 1 | | SB | 8 bit data | PB | STB | |
249 +---------------------------------------------------------------+
254 * @brief Initialize the SMARTCARD mode according to the specified
255 * parameters in the SMARTCARD_HandleTypeDef and initialize the associated handle.
256 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
257 * the configuration information for the specified SMARTCARD module.
258 * @retval HAL status
260 HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsmartcard)
262 /* Check the SMARTCARD handle allocation */
263 if(hsmartcard == NULL)
265 return HAL_ERROR;
268 /* Check the USART associated to the SMARTCARD handle */
269 assert_param(IS_SMARTCARD_INSTANCE(hsmartcard->Instance));
271 if(hsmartcard->gState == HAL_SMARTCARD_STATE_RESET)
273 /* Allocate lock resource and initialize it */
274 hsmartcard->Lock = HAL_UNLOCKED;
276 /* Init the low level hardware : GPIO, CLOCK */
277 HAL_SMARTCARD_MspInit(hsmartcard);
280 hsmartcard->gState = HAL_SMARTCARD_STATE_BUSY;
282 /* Disable the Peripheral to set smartcard mode */
283 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
285 /* In SmartCard mode, the following bits must be kept cleared:
286 - LINEN in the USART_CR2 register,
287 - HDSEL and IREN bits in the USART_CR3 register.*/
288 CLEAR_BIT(hsmartcard->Instance->CR2, USART_CR2_LINEN);
289 CLEAR_BIT(hsmartcard->Instance->CR3, (USART_CR3_HDSEL | USART_CR3_IREN));
291 /* set the USART in SMARTCARD mode */
292 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_SCEN);
294 /* Set the SMARTCARD Communication parameters */
295 if (SMARTCARD_SetConfig(hsmartcard) == HAL_ERROR)
297 return HAL_ERROR;
300 if (hsmartcard->AdvancedInit.AdvFeatureInit != SMARTCARD_ADVFEATURE_NO_INIT)
302 SMARTCARD_AdvFeatureConfig(hsmartcard);
305 /* Enable the Peripheral */
306 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
308 /* TEACK and/or REACK to check before moving hsmartcard->gState and hsmartcard->RxState to Ready */
309 return (SMARTCARD_CheckIdleState(hsmartcard));
313 * @brief DeInitialize the SMARTCARD peripheral.
314 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
315 * the configuration information for the specified SMARTCARD module.
316 * @retval HAL status
318 HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsmartcard)
320 /* Check the SMARTCARD handle allocation */
321 if(hsmartcard == NULL)
323 return HAL_ERROR;
326 /* Check the USART/UART associated to the SMARTCARD handle */
327 assert_param(IS_SMARTCARD_INSTANCE(hsmartcard->Instance));
329 hsmartcard->gState = HAL_SMARTCARD_STATE_BUSY;
331 /* Disable the Peripheral */
332 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
334 WRITE_REG(hsmartcard->Instance->CR1, 0x0U);
335 WRITE_REG(hsmartcard->Instance->CR2, 0x0U);
336 WRITE_REG(hsmartcard->Instance->CR3, 0x0U);
337 WRITE_REG(hsmartcard->Instance->RTOR, 0x0U);
338 WRITE_REG(hsmartcard->Instance->GTPR, 0x0U);
340 /* DeInit the low level hardware */
341 HAL_SMARTCARD_MspDeInit(hsmartcard);
343 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
344 hsmartcard->gState = HAL_SMARTCARD_STATE_RESET;
345 hsmartcard->RxState = HAL_SMARTCARD_STATE_RESET;
347 /* Process Unlock */
348 __HAL_UNLOCK(hsmartcard);
350 return HAL_OK;
354 * @brief Initialize the SMARTCARD MSP.
355 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
356 * the configuration information for the specified SMARTCARD module.
357 * @retval None
359 __weak void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsmartcard)
361 /* Prevent unused argument(s) compilation warning */
362 UNUSED(hsmartcard);
364 /* NOTE : This function should not be modified, when the callback is needed,
365 the HAL_SMARTCARD_MspInit can be implemented in the user file
370 * @brief DeInitialize the SMARTCARD MSP.
371 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
372 * the configuration information for the specified SMARTCARD module.
373 * @retval None
375 __weak void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsmartcard)
377 /* Prevent unused argument(s) compilation warning */
378 UNUSED(hsmartcard);
380 /* NOTE : This function should not be modified, when the callback is needed,
381 the HAL_SMARTCARD_MspDeInit can be implemented in the user file
386 * @}
389 /** @defgroup SMARTCARD_Exported_Functions_Group2 IO operation functions
390 * @brief SMARTCARD Transmit and Receive functions
392 @verbatim
393 ==============================================================================
394 ##### IO operation functions #####
395 ==============================================================================
396 [..]
397 This subsection provides a set of functions allowing to manage the SMARTCARD data transfers.
399 [..]
400 Smartcard is a single wire half duplex communication protocol.
401 The Smartcard interface is designed to support asynchronous protocol Smartcards as
402 defined in the ISO 7816-3 standard. The USART should be configured as:
403 (+) 8 bits plus parity: where M=1 and PCE=1 in the USART_CR1 register
404 (+) 1.5 stop bits when transmitting and receiving: where STOP=11 in the USART_CR2 register.
406 [..]
407 (#) There are two modes of transfer:
408 (++) Blocking mode: The communication is performed in polling mode.
409 The HAL status of all data processing is returned by the same function
410 after finishing transfer.
411 (++) Non-Blocking mode: The communication is performed using Interrupts
412 or DMA, the relevant API's return the HAL status.
413 The end of the data processing will be indicated through the
414 dedicated SMARTCARD IRQ when using Interrupt mode or the DMA IRQ when
415 using DMA mode.
416 (++) The HAL_SMARTCARD_TxCpltCallback(), HAL_SMARTCARD_RxCpltCallback() user callbacks
417 will be executed respectively at the end of the Transmit or Receive process
418 The HAL_SMARTCARD_ErrorCallback() user callback will be executed when a communication
419 error is detected.
421 (#) Blocking mode APIs are :
422 (++) HAL_SMARTCARD_Transmit()
423 (++) HAL_SMARTCARD_Receive()
425 (#) Non Blocking mode APIs with Interrupt are :
426 (++) HAL_SMARTCARD_Transmit_IT()
427 (++) HAL_SMARTCARD_Receive_IT()
428 (++) HAL_SMARTCARD_IRQHandler()
430 (#) Non Blocking mode functions with DMA are :
431 (++) HAL_SMARTCARD_Transmit_DMA()
432 (++) HAL_SMARTCARD_Receive_DMA()
434 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
435 (++) HAL_SMARTCARD_TxCpltCallback()
436 (++) HAL_SMARTCARD_RxCpltCallback()
437 (++) HAL_SMARTCARD_ErrorCallback()
439 (#) Non-Blocking mode transfers could be aborted using Abort API's :
440 (++) HAL_SMARTCARD_Abort()
441 (++) HAL_SMARTCARD_AbortTransmit()
442 (++) HAL_SMARTCARD_AbortReceive()
443 (++) HAL_SMARTCARD_Abort_IT()
444 (++) HAL_SMARTCARD_AbortTransmit_IT()
445 (++) HAL_SMARTCARD_AbortReceive_IT()
447 (#) For Abort services based on interrupts (HAL_SMARTCARD_Abortxxx_IT), a set of Abort Complete Callbacks are provided:
448 (++) HAL_SMARTCARD_AbortCpltCallback()
449 (++) HAL_SMARTCARD_AbortTransmitCpltCallback()
450 (++) HAL_SMARTCARD_AbortReceiveCpltCallback()
452 (#) In Non-Blocking mode transfers, possible errors are split into 2 categories.
453 Errors are handled as follows :
454 (++) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is
455 to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception .
456 Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type,
457 and HAL_SMARTCARD_ErrorCallback() user callback is executed. Transfer is kept ongoing on SMARTCARD side.
458 If user wants to abort it, Abort services should be called by user.
459 (++) Error is considered as Blocking : Transfer could not be completed properly and is aborted.
460 This concerns Frame Error in Interrupt mode tranmission, Overrun Error in Interrupt mode reception and all errors in DMA mode.
461 Error code is set to allow user to identify error type, and HAL_SMARTCARD_ErrorCallback() user callback is executed.
463 @endverbatim
464 * @{
468 * @brief Send an amount of data in blocking mode.
469 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
470 * the configuration information for the specified SMARTCARD module.
471 * @param pData pointer to data buffer.
472 * @param Size amount of data to be sent.
473 * @param Timeout Timeout duration.
474 * @retval HAL status
476 HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size, uint32_t Timeout)
478 uint32_t tickstart = 0U;
480 /* Check that a Tx process is not already ongoing */
481 if (hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
483 if((pData == NULL) || (Size == 0U))
485 return HAL_ERROR;
488 /* Process Locked */
489 __HAL_LOCK(hsmartcard);
491 hsmartcard->gState = HAL_SMARTCARD_STATE_BUSY_TX;
493 /* Init tickstart for timeout managment*/
494 tickstart = HAL_GetTick();
496 /* Disable the Peripheral first to update mode for TX master */
497 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
499 /* Disable Rx, enable Tx */
500 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_RE);
501 SET_BIT(hsmartcard->Instance->RQR, SMARTCARD_RXDATA_FLUSH_REQUEST);
502 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_TE);
504 /* Enable the Peripheral */
505 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
507 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
508 hsmartcard->TxXferSize = Size;
509 hsmartcard->TxXferCount = Size;
511 while(hsmartcard->TxXferCount > 0U)
513 hsmartcard->TxXferCount--;
514 if(SMARTCARD_WaitOnFlagUntilTimeout(hsmartcard, SMARTCARD_FLAG_TXE, RESET, tickstart, Timeout) != HAL_OK)
516 return HAL_TIMEOUT;
518 hsmartcard->Instance->TDR = (*pData++ & (uint8_t)0xFFU);
520 if(SMARTCARD_WaitOnFlagUntilTimeout(hsmartcard, SMARTCARD_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
522 return HAL_TIMEOUT;
524 /* Re-enable Rx at end of transmission if initial mode is Rx/Tx */
525 if(hsmartcard->Init.Mode == SMARTCARD_MODE_TX_RX)
527 /* Disable the Peripheral first to update modes */
528 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
529 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_RE);
530 /* Enable the Peripheral */
531 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
534 /* At end of Tx process, restore hsmartcard->gState to Ready */
535 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
537 /* Process Unlocked */
538 __HAL_UNLOCK(hsmartcard);
540 return HAL_OK;
542 else
544 return HAL_BUSY;
549 * @brief Receive an amount of data in blocking mode.
550 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
551 * the configuration information for the specified SMARTCARD module.
552 * @param pData pointer to data buffer.
553 * @param Size amount of data to be received.
554 * @param Timeout Timeout duration.
555 * @retval HAL status
557 HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size, uint32_t Timeout)
559 uint32_t tickstart = 0U;
561 /* Check that a Rx process is not already ongoing */
562 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
564 if((pData == NULL) || (Size == 0U))
566 return HAL_ERROR;
569 /* Process Locked */
570 __HAL_LOCK(hsmartcard);
572 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
573 hsmartcard->RxState = HAL_SMARTCARD_STATE_BUSY_RX;
575 /* Init tickstart for timeout managment*/
576 tickstart = HAL_GetTick();
578 hsmartcard->RxXferSize = Size;
579 hsmartcard->RxXferCount = Size;
581 /* Check the remain data to be received */
582 while(hsmartcard->RxXferCount > 0U)
584 hsmartcard->RxXferCount--;
586 if(SMARTCARD_WaitOnFlagUntilTimeout(hsmartcard, SMARTCARD_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
588 return HAL_TIMEOUT;
590 *pData++ = (uint8_t)(hsmartcard->Instance->RDR & (uint8_t)0x00FF);
593 /* At end of Rx process, restore hsmartcard->RxState to Ready */
594 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
596 /* Process Unlocked */
597 __HAL_UNLOCK(hsmartcard);
599 return HAL_OK;
601 else
603 return HAL_BUSY;
608 * @brief Send an amount of data in interrupt mode.
609 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
610 * the configuration information for the specified SMARTCARD module.
611 * @param pData pointer to data buffer.
612 * @param Size amount of data to be sent.
613 * @retval HAL status
615 HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size)
617 /* Check that a Tx process is not already ongoing */
618 if (hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
620 if((pData == NULL) || (Size == 0U))
622 return HAL_ERROR;
625 /* Process Locked */
626 __HAL_LOCK(hsmartcard);
628 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
629 hsmartcard->gState = HAL_SMARTCARD_STATE_BUSY_TX;
631 hsmartcard->pTxBuffPtr = pData;
632 hsmartcard->TxXferSize = Size;
633 hsmartcard->TxXferCount = Size;
635 /* Disable the Peripheral first to update mode for TX master */
636 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
638 /* Disable Rx, enable Tx */
639 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_RE);
640 SET_BIT(hsmartcard->Instance->RQR, SMARTCARD_RXDATA_FLUSH_REQUEST);
641 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_TE);
643 /* Enable the Peripheral */
644 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
646 /* Process Unlocked */
647 __HAL_UNLOCK(hsmartcard);
649 /* Enable the SMARTCARD Error Interrupt: (Frame error) */
650 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
652 /* Enable the SMARTCARD Transmit Data Register Empty Interrupt */
653 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_TXEIE);
655 return HAL_OK;
657 else
659 return HAL_BUSY;
664 * @brief Receive an amount of data in interrupt mode.
665 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
666 * the configuration information for the specified SMARTCARD module.
667 * @param pData pointer to data buffer.
668 * @param Size amount of data to be received.
669 * @retval HAL status
671 HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size)
673 /* Check that a Rx process is not already ongoing */
674 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
676 if((pData == NULL) || (Size == 0U))
678 return HAL_ERROR;
681 /* Process Locked */
682 __HAL_LOCK(hsmartcard);
684 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
685 hsmartcard->RxState = HAL_SMARTCARD_STATE_BUSY_RX;
687 hsmartcard->pRxBuffPtr = pData;
688 hsmartcard->RxXferSize = Size;
689 hsmartcard->RxXferCount = Size;
691 /* Process Unlocked */
692 __HAL_UNLOCK(hsmartcard);
694 /* Enable the SMARTCARD Parity Error and Data Register not empty Interrupts */
695 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_PEIE| USART_CR1_RXNEIE);
697 /* Enable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */
698 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
700 return HAL_OK;
702 else
704 return HAL_BUSY;
709 * @brief Send an amount of data in DMA mode.
710 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
711 * the configuration information for the specified SMARTCARD module.
712 * @param pData pointer to data buffer.
713 * @param Size amount of data to be sent.
714 * @retval HAL status
716 HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size)
718 /* Check that a Tx process is not already ongoing */
719 if (hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
721 if((pData == NULL) || (Size == 0U))
723 return HAL_ERROR;
726 /* Process Locked */
727 __HAL_LOCK(hsmartcard);
729 hsmartcard->gState = HAL_SMARTCARD_STATE_BUSY_TX;
731 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
732 hsmartcard->pTxBuffPtr = pData;
733 hsmartcard->TxXferSize = Size;
734 hsmartcard->TxXferCount = Size;
736 /* Disable the Peripheral first to update mode for TX master */
737 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
739 /* Disable Rx, enable Tx */
740 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_RE);
741 SET_BIT(hsmartcard->Instance->RQR, SMARTCARD_RXDATA_FLUSH_REQUEST);
742 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_TE);
744 /* Enable the Peripheral */
745 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
747 /* Set the SMARTCARD DMA transfer complete callback */
748 hsmartcard->hdmatx->XferCpltCallback = SMARTCARD_DMATransmitCplt;
750 /* Set the SMARTCARD error callback */
751 hsmartcard->hdmatx->XferErrorCallback = SMARTCARD_DMAError;
753 /* Set the DMA abort callback */
754 hsmartcard->hdmatx->XferAbortCallback = NULL;
756 /* Enable the SMARTCARD transmit DMA channel */
757 HAL_DMA_Start_IT(hsmartcard->hdmatx, (uint32_t)hsmartcard->pTxBuffPtr, (uint32_t)&hsmartcard->Instance->TDR, Size);
759 /* Clear the TC flag in the ICR register */
760 CLEAR_BIT(hsmartcard->Instance->ICR, USART_ICR_TCCF);
762 /* Process Unlocked */
763 __HAL_UNLOCK(hsmartcard);
765 /* Enable the UART Error Interrupt: (Frame error) */
766 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
768 /* Enable the DMA transfer for transmit request by setting the DMAT bit
769 in the SMARTCARD associated USART CR3 register */
770 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
772 return HAL_OK;
774 else
776 return HAL_BUSY;
781 * @brief Receive an amount of data in DMA mode.
782 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
783 * the configuration information for the specified SMARTCARD module.
784 * @param pData pointer to data buffer.
785 * @param Size amount of data to be received.
786 * @note The SMARTCARD-associated USART parity is enabled (PCE = 1),
787 * the received data contain the parity bit (MSB position).
788 * @retval HAL status
790 HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsmartcard, uint8_t *pData, uint16_t Size)
792 /* Check that a Rx process is not already ongoing */
793 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
795 if((pData == NULL) || (Size == 0U))
797 return HAL_ERROR;
800 /* Process Locked */
801 __HAL_LOCK(hsmartcard);
803 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
804 hsmartcard->RxState = HAL_SMARTCARD_STATE_BUSY_RX;
806 hsmartcard->pRxBuffPtr = pData;
807 hsmartcard->RxXferSize = Size;
809 /* Set the SMARTCARD DMA transfer complete callback */
810 hsmartcard->hdmarx->XferCpltCallback = SMARTCARD_DMAReceiveCplt;
812 /* Set the SMARTCARD DMA error callback */
813 hsmartcard->hdmarx->XferErrorCallback = SMARTCARD_DMAError;
815 /* Set the DMA abort callback */
816 hsmartcard->hdmarx->XferAbortCallback = NULL;
818 /* Enable the DMA channel */
819 HAL_DMA_Start_IT(hsmartcard->hdmarx, (uint32_t)&hsmartcard->Instance->RDR, (uint32_t)hsmartcard->pRxBuffPtr, Size);
821 /* Process Unlocked */
822 __HAL_UNLOCK(hsmartcard);
824 /* Enable the UART Parity Error Interrupt */
825 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_PEIE);
827 /* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
828 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
830 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
831 in the SMARTCARD associated USART CR3 register */
832 SET_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
834 return HAL_OK;
836 else
838 return HAL_BUSY;
843 * @brief Abort ongoing transfers (blocking mode).
844 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
845 * the configuration information for the specified SMARTCARD module.
846 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
847 * This procedure performs following operations :
848 * - Disable SMARTCARD Interrupts (Tx and Rx)
849 * - Disable the DMA transfer in the peripheral register (if enabled)
850 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
851 * - Set handle State to READY
852 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
853 * @retval HAL status
855 HAL_StatusTypeDef HAL_SMARTCARD_Abort(SMARTCARD_HandleTypeDef *hsmartcard)
857 /* Disable RTOIE, EOBIE, TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
858 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RTOIE | USART_CR1_EOBIE));
859 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
861 /* Disable the SMARTCARD DMA Tx request if enabled */
862 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
864 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
866 /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */
867 if(hsmartcard->hdmatx != NULL)
869 /* Set the SMARTCARD DMA Abort callback to Null.
870 No call back execution at end of DMA abort procedure */
871 hsmartcard->hdmatx->XferAbortCallback = NULL;
873 HAL_DMA_Abort(hsmartcard->hdmatx);
877 /* Disable the SMARTCARD DMA Rx request if enabled */
878 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
880 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
882 /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */
883 if(hsmartcard->hdmarx != NULL)
885 /* Set the SMARTCARD DMA Abort callback to Null.
886 No call back execution at end of DMA abort procedure */
887 hsmartcard->hdmarx->XferAbortCallback = NULL;
889 HAL_DMA_Abort(hsmartcard->hdmarx);
893 /* Reset Tx and Rx transfer counters */
894 hsmartcard->TxXferCount = 0U;
895 hsmartcard->RxXferCount = 0U;
897 /* Clear the Error flags in the ICR register */
898 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
900 /* Restore hsmartcard->gState and hsmartcard->RxState to Ready */
901 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
902 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
904 /* Reset Handle ErrorCode to No Error */
905 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
907 return HAL_OK;
911 * @brief Abort ongoing Transmit transfer (blocking mode).
912 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
913 * the configuration information for the specified SMARTCARD module.
914 * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode.
915 * This procedure performs following operations :
916 * - Disable SMARTCARD Interrupts (Tx)
917 * - Disable the DMA transfer in the peripheral register (if enabled)
918 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
919 * - Set handle State to READY
920 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
921 * @retval HAL status
923 HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit(SMARTCARD_HandleTypeDef *hsmartcard)
925 /* Disable TXEIE and TCIE interrupts */
926 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
928 /* Check if a receive process is ongoing or not. If not disable ERR IT */
929 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
931 /* Disable the SMARTCARD Error Interrupt: (Frame error) */
932 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
935 /* Disable the SMARTCARD DMA Tx request if enabled */
936 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
938 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
940 /* Abort the SMARTCARD DMA Tx channel : use blocking DMA Abort API (no callback) */
941 if(hsmartcard->hdmatx != NULL)
943 /* Set the SMARTCARD DMA Abort callback to Null.
944 No call back execution at end of DMA abort procedure */
945 hsmartcard->hdmatx->XferAbortCallback = NULL;
947 HAL_DMA_Abort(hsmartcard->hdmatx);
951 /* Reset Tx transfer counter */
952 hsmartcard->TxXferCount = 0U;
954 /* Clear the Error flags in the ICR register */
955 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_FEF);
957 /* Restore hsmartcard->gState to Ready */
958 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
960 return HAL_OK;
964 * @brief Abort ongoing Receive transfer (blocking mode).
965 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
966 * the configuration information for the specified SMARTCARD module.
967 * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode.
968 * This procedure performs following operations :
969 * - Disable SMARTCARD Interrupts (Rx)
970 * - Disable the DMA transfer in the peripheral register (if enabled)
971 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
972 * - Set handle State to READY
973 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
974 * @retval HAL status
976 HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive(SMARTCARD_HandleTypeDef *hsmartcard)
978 /* Disable RTOIE, EOBIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
979 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_RTOIE | USART_CR1_EOBIE));
981 /* Check if a Transmit process is ongoing or not. If not disable ERR IT */
982 if(hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
984 /* Disable the SMARTCARD Error Interrupt: (Frame error) */
985 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
988 /* Disable the SMARTCARD DMA Rx request if enabled */
989 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
991 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
993 /* Abort the SMARTCARD DMA Rx channel : use blocking DMA Abort API (no callback) */
994 if(hsmartcard->hdmarx != NULL)
996 /* Set the SMARTCARD DMA Abort callback to Null.
997 No call back execution at end of DMA abort procedure */
998 hsmartcard->hdmarx->XferAbortCallback = NULL;
1000 HAL_DMA_Abort(hsmartcard->hdmarx);
1004 /* Reset Rx transfer counter */
1005 hsmartcard->RxXferCount = 0U;
1007 /* Clear the Error flags in the ICR register */
1008 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
1010 /* Restore hsmartcard->RxState to Ready */
1011 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1013 return HAL_OK;
1017 * @brief Abort ongoing transfers (Interrupt mode).
1018 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1019 * the configuration information for the specified SMARTCARD module.
1020 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1021 * This procedure performs following operations :
1022 * - Disable SMARTCARD Interrupts (Tx and Rx)
1023 * - Disable the DMA transfer in the peripheral register (if enabled)
1024 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1025 * - Set handle State to READY
1026 * - At abort completion, call user abort complete callback
1027 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1028 * considered as completed only when user abort complete callback is executed (not when exiting function).
1029 * @retval HAL status
1031 HAL_StatusTypeDef HAL_SMARTCARD_Abort_IT(SMARTCARD_HandleTypeDef *hsmartcard)
1033 uint32_t abortcplt = 1U;
1035 /* Disable RTOIE, EOBIE, TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1036 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RTOIE | USART_CR1_EOBIE));
1037 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1039 /* If DMA Tx and/or DMA Rx Handles are associated to SMARTCARD Handle, DMA Abort complete callbacks should be initialised
1040 before any call to DMA Abort functions */
1041 /* DMA Tx Handle is valid */
1042 if(hsmartcard->hdmatx != NULL)
1044 /* Set DMA Abort Complete callback if SMARTCARD DMA Tx request if enabled.
1045 Otherwise, set it to NULL */
1046 if(HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
1048 hsmartcard->hdmatx->XferAbortCallback = SMARTCARD_DMATxAbortCallback;
1050 else
1052 hsmartcard->hdmatx->XferAbortCallback = NULL;
1055 /* DMA Rx Handle is valid */
1056 if(hsmartcard->hdmarx != NULL)
1058 /* Set DMA Abort Complete callback if SMARTCARD DMA Rx request if enabled.
1059 Otherwise, set it to NULL */
1060 if(HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
1062 hsmartcard->hdmarx->XferAbortCallback = SMARTCARD_DMARxAbortCallback;
1064 else
1066 hsmartcard->hdmarx->XferAbortCallback = NULL;
1070 /* Disable the SMARTCARD DMA Tx request if enabled */
1071 if(HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
1073 /* Disable DMA Tx at UART level */
1074 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
1076 /* Abort the SMARTCARD DMA Tx channel : use non blocking DMA Abort API (callback) */
1077 if(hsmartcard->hdmatx != NULL)
1079 /* SMARTCARD Tx DMA Abort callback has already been initialised :
1080 will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */
1082 /* Abort DMA TX */
1083 if(HAL_DMA_Abort_IT(hsmartcard->hdmatx) != HAL_OK)
1085 hsmartcard->hdmatx->XferAbortCallback = NULL;
1087 else
1089 abortcplt = 0U;
1094 /* Disable the SMARTCARD DMA Rx request if enabled */
1095 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
1097 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
1099 /* Abort the SMARTCARD DMA Rx channel : use non blocking DMA Abort API (callback) */
1100 if(hsmartcard->hdmarx != NULL)
1102 /* SMARTCARD Rx DMA Abort callback has already been initialised :
1103 will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */
1105 /* Abort DMA RX */
1106 if(HAL_DMA_Abort_IT(hsmartcard->hdmarx) != HAL_OK)
1108 hsmartcard->hdmarx->XferAbortCallback = NULL;
1109 abortcplt = 1U;
1111 else
1113 abortcplt = 0U;
1118 /* if no DMA abort complete callback execution is required => call user Abort Complete callback */
1119 if (abortcplt == 1U)
1121 /* Reset Tx and Rx transfer counters */
1122 hsmartcard->TxXferCount = 0U;
1123 hsmartcard->RxXferCount = 0U;
1125 /* Reset errorCode */
1126 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
1128 /* Clear the Error flags in the ICR register */
1129 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
1131 /* Restore hsmartcard->gState and hsmartcard->RxState to Ready */
1132 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1133 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1135 /* As no DMA to be aborted, call directly user Abort complete callback */
1136 HAL_SMARTCARD_AbortCpltCallback(hsmartcard);
1139 return HAL_OK;
1143 * @brief Abort ongoing Transmit transfer (Interrupt mode).
1144 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1145 * the configuration information for the specified SMARTCARD module.
1146 * @note This procedure could be used for aborting any ongoing Tx transfer started in Interrupt or DMA mode.
1147 * This procedure performs following operations :
1148 * - Disable SMARTCARD Interrupts (Tx)
1149 * - Disable the DMA transfer in the peripheral register (if enabled)
1150 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1151 * - Set handle State to READY
1152 * - At abort completion, call user abort complete callback
1153 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1154 * considered as completed only when user abort complete callback is executed (not when exiting function).
1155 * @retval HAL status
1157 HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit_IT(SMARTCARD_HandleTypeDef *hsmartcard)
1159 /* Disable TXEIE and TCIE interrupts */
1160 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1162 /* Check if a receive process is ongoing or not. If not disable ERR IT */
1163 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
1165 /* Disable the SMARTCARD Error Interrupt: (Frame error) */
1166 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1169 /* Disable the SMARTCARD DMA Tx request if enabled */
1170 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
1172 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
1174 /* Abort the SMARTCARD DMA Tx channel : use non blocking DMA Abort API (callback) */
1175 if(hsmartcard->hdmatx != NULL)
1177 /* Set the SMARTCARD DMA Abort callback :
1178 will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */
1179 hsmartcard->hdmatx->XferAbortCallback = SMARTCARD_DMATxOnlyAbortCallback;
1181 /* Abort DMA TX */
1182 if(HAL_DMA_Abort_IT(hsmartcard->hdmatx) != HAL_OK)
1184 /* Call Directly hsmartcard->hdmatx->XferAbortCallback function in case of error */
1185 hsmartcard->hdmatx->XferAbortCallback(hsmartcard->hdmatx);
1188 else
1190 /* Reset Tx transfer counter */
1191 hsmartcard->TxXferCount = 0U;
1193 /* Restore hsmartcard->gState to Ready */
1194 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1196 /* As no DMA to be aborted, call directly user Abort complete callback */
1197 HAL_SMARTCARD_AbortTransmitCpltCallback(hsmartcard);
1200 else
1202 /* Reset Tx transfer counter */
1203 hsmartcard->TxXferCount = 0U;
1205 /* Clear the Error flags in the ICR register */
1206 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_FEF);
1208 /* Restore hsmartcard->gState to Ready */
1209 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1211 /* As no DMA to be aborted, call directly user Abort complete callback */
1212 HAL_SMARTCARD_AbortTransmitCpltCallback(hsmartcard);
1215 return HAL_OK;
1219 * @brief Abort ongoing Receive transfer (Interrupt mode).
1220 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1221 * the configuration information for the specified SMARTCARD module.
1222 * @note This procedure could be used for aborting any ongoing Rx transfer started in Interrupt or DMA mode.
1223 * This procedure performs following operations :
1224 * - Disable SMARTCARD Interrupts (Rx)
1225 * - Disable the DMA transfer in the peripheral register (if enabled)
1226 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1227 * - Set handle State to READY
1228 * - At abort completion, call user abort complete callback
1229 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1230 * considered as completed only when user abort complete callback is executed (not when exiting function).
1231 * @retval HAL status
1233 HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive_IT(SMARTCARD_HandleTypeDef *hsmartcard)
1235 /* Disable RTOIE, EOBIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1236 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_RTOIE | USART_CR1_EOBIE));
1238 /* Check if a Transmit process is ongoing or not. If not disable ERR IT */
1239 if(hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
1241 /* Disable the SMARTCARD Error Interrupt: (Frame error) */
1242 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1245 /* Disable the SMARTCARD DMA Rx request if enabled */
1246 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
1248 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
1250 /* Abort the SMARTCARD DMA Rx channel : use non blocking DMA Abort API (callback) */
1251 if(hsmartcard->hdmarx != NULL)
1253 /* Set the SMARTCARD DMA Abort callback :
1254 will lead to call HAL_SMARTCARD_AbortCpltCallback() at end of DMA abort procedure */
1255 hsmartcard->hdmarx->XferAbortCallback = SMARTCARD_DMARxOnlyAbortCallback;
1257 /* Abort DMA RX */
1258 if(HAL_DMA_Abort_IT(hsmartcard->hdmarx) != HAL_OK)
1260 /* Call Directly hsmartcard->hdmarx->XferAbortCallback function in case of error */
1261 hsmartcard->hdmarx->XferAbortCallback(hsmartcard->hdmarx);
1264 else
1266 /* Reset Rx transfer counter */
1267 hsmartcard->RxXferCount = 0U;
1269 /* Clear the Error flags in the ICR register */
1270 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
1272 /* Restore hsmartcard->RxState to Ready */
1273 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1275 /* As no DMA to be aborted, call directly user Abort complete callback */
1276 HAL_SMARTCARD_AbortReceiveCpltCallback(hsmartcard);
1279 else
1281 /* Reset Rx transfer counter */
1282 hsmartcard->RxXferCount = 0U;
1284 /* Clear the Error flags in the ICR register */
1285 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
1287 /* Restore hsmartcard->RxState to Ready */
1288 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1290 /* As no DMA to be aborted, call directly user Abort complete callback */
1291 HAL_SMARTCARD_AbortReceiveCpltCallback(hsmartcard);
1294 return HAL_OK;
1298 * @brief Handle SMARTCARD interrupt requests.
1299 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1300 * the configuration information for the specified SMARTCARD module.
1301 * @retval None
1303 void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsmartcard)
1305 uint32_t isrflags = READ_REG(hsmartcard->Instance->ISR);
1306 uint32_t cr1its = READ_REG(hsmartcard->Instance->CR1);
1307 uint32_t cr3its;
1308 uint32_t errorflags;
1310 /* If no error occurs */
1311 errorflags = (isrflags & (uint32_t)(USART_ISR_PE | USART_ISR_FE | USART_ISR_ORE | USART_ISR_NE | USART_ISR_RTOF));
1312 if (errorflags == RESET)
1314 /* SMARTCARD in mode Receiver ---------------------------------------------------*/
1315 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1317 SMARTCARD_Receive_IT(hsmartcard);
1318 /* Clear RXNE interrupt flag done by reading RDR in SMARTCARD_Receive_IT() */
1319 return;
1323 /* If some errors occur */
1324 cr3its = READ_REG(hsmartcard->Instance->CR3);
1325 if( (errorflags != RESET)
1326 && ( ((cr3its & USART_CR3_EIE) != RESET)
1327 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_RTOIE)) != RESET)) )
1329 /* SMARTCARD parity error interrupt occurred -------------------------------------*/
1330 if(((isrflags & USART_ISR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET))
1332 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_PEF);
1334 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_PE;
1337 /* SMARTCARD frame error interrupt occurred --------------------------------------*/
1338 if(((isrflags & USART_ISR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1340 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_FEF);
1342 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_FE;
1345 /* SMARTCARD noise error interrupt occurred --------------------------------------*/
1346 if(((isrflags & USART_ISR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1348 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_NEF);
1350 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_NE;
1353 /* SMARTCARD Over-Run interrupt occurred -----------------------------------------*/
1354 if(((isrflags & USART_ISR_ORE) != RESET) &&
1355 (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET)))
1357 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_OREF);
1359 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_ORE;
1362 /* SMARTCARD receiver timeout interrupt occurred -----------------------------------------*/
1363 if(((isrflags & USART_ISR_RTOF) != RESET) && ((cr1its & USART_CR1_RTOIE) != RESET))
1365 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_RTOF);
1367 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_RTO;
1370 /* Call SMARTCARD Error Call back function if need be --------------------------*/
1371 if(hsmartcard->ErrorCode != HAL_SMARTCARD_ERROR_NONE)
1373 /* SMARTCARD in mode Receiver ---------------------------------------------------*/
1374 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1376 SMARTCARD_Receive_IT(hsmartcard);
1379 /* If Error is to be considered as blocking :
1380 - Receiver Timeout error in Reception
1381 - Overrun error in Reception
1382 - any error occurs in DMA mode reception
1384 if ( ((hsmartcard->ErrorCode & (HAL_SMARTCARD_ERROR_RTO | HAL_SMARTCARD_ERROR_ORE)) != RESET)
1385 || (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR)))
1387 /* Blocking error : transfer is aborted
1388 Set the SMARTCARD state ready to be able to start again the process,
1389 Disable Rx Interrupts, and disable Rx DMA request, if ongoing */
1390 SMARTCARD_EndRxTransfer(hsmartcard);
1392 /* Disable the SMARTCARD DMA Rx request if enabled */
1393 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR))
1395 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
1397 /* Abort the SMARTCARD DMA Rx channel */
1398 if(hsmartcard->hdmarx != NULL)
1400 /* Set the SMARTCARD DMA Abort callback :
1401 will lead to call HAL_SMARTCARD_ErrorCallback() at end of DMA abort procedure */
1402 hsmartcard->hdmarx->XferAbortCallback = SMARTCARD_DMAAbortOnError;
1404 /* Abort DMA RX */
1405 if(HAL_DMA_Abort_IT(hsmartcard->hdmarx) != HAL_OK)
1407 /* Call Directly hsmartcard->hdmarx->XferAbortCallback function in case of error */
1408 hsmartcard->hdmarx->XferAbortCallback(hsmartcard->hdmarx);
1411 else
1413 /* Call user error callback */
1414 HAL_SMARTCARD_ErrorCallback(hsmartcard);
1417 else
1419 /* Call user error callback */
1420 HAL_SMARTCARD_ErrorCallback(hsmartcard);
1423 /* other error type to be considered as blocking :
1424 - Frame error in Transmission
1426 else if ((hsmartcard->gState == HAL_SMARTCARD_STATE_BUSY_TX) && ((hsmartcard->ErrorCode & HAL_SMARTCARD_ERROR_FE) != RESET))
1428 /* Blocking error : transfer is aborted
1429 Set the SMARTCARD state ready to be able to start again the process,
1430 Disable Tx Interrupts, and disable Tx DMA request, if ongoing */
1431 SMARTCARD_EndTxTransfer(hsmartcard);
1433 /* Disable the SMARTCARD DMA Tx request if enabled */
1434 if (HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT))
1436 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
1438 /* Abort the SMARTCARD DMA Tx channel */
1439 if(hsmartcard->hdmatx != NULL)
1441 /* Set the SMARTCARD DMA Abort callback :
1442 will lead to call HAL_SMARTCARD_ErrorCallback() at end of DMA abort procedure */
1443 hsmartcard->hdmatx->XferAbortCallback = SMARTCARD_DMAAbortOnError;
1445 /* Abort DMA TX */
1446 if(HAL_DMA_Abort_IT(hsmartcard->hdmatx) != HAL_OK)
1448 /* Call Directly hsmartcard->hdmatx->XferAbortCallback function in case of error */
1449 hsmartcard->hdmatx->XferAbortCallback(hsmartcard->hdmatx);
1452 else
1454 /* Call user error callback */
1455 HAL_SMARTCARD_ErrorCallback(hsmartcard);
1458 else
1460 /* Call user error callback */
1461 HAL_SMARTCARD_ErrorCallback(hsmartcard);
1464 else
1466 /* Non Blocking error : transfer could go on.
1467 Error is notified to user through user error callback */
1468 HAL_SMARTCARD_ErrorCallback(hsmartcard);
1469 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
1472 return;
1474 } /* End if some error occurs */
1476 /* SMARTCARD in mode Receiver, end of block interruption ------------------------*/
1477 if(((isrflags & USART_ISR_EOBF) != RESET) && ((cr1its & USART_CR1_EOBIE) != RESET))
1479 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1480 __HAL_UNLOCK(hsmartcard);
1481 HAL_SMARTCARD_RxCpltCallback(hsmartcard);
1482 /* Clear EOBF interrupt after HAL_SMARTCARD_RxCpltCallback() call for the End of Block information
1483 * to be available during HAL_SMARTCARD_RxCpltCallback() processing */
1484 __HAL_SMARTCARD_CLEAR_IT(hsmartcard, SMARTCARD_CLEAR_EOBF);
1485 return;
1488 /* SMARTCARD in mode Transmitter ------------------------------------------------*/
1489 if(((isrflags & USART_ISR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET))
1491 SMARTCARD_Transmit_IT(hsmartcard);
1492 return;
1495 /* SMARTCARD in mode Transmitter (transmission end) ------------------------*/
1496 if((__HAL_SMARTCARD_GET_IT(hsmartcard, SMARTCARD_IT_TC) != RESET) &&(__HAL_SMARTCARD_GET_IT_SOURCE(hsmartcard, SMARTCARD_IT_TC) != RESET))
1498 SMARTCARD_EndTransmit_IT(hsmartcard);
1499 return;
1504 * @brief Tx Transfer completed callback.
1505 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1506 * the configuration information for the specified SMARTCARD module.
1507 * @retval None
1509 __weak void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsmartcard)
1511 /* Prevent unused argument(s) compilation warning */
1512 UNUSED(hsmartcard);
1514 /* NOTE : This function should not be modified, when the callback is needed,
1515 the HAL_SMARTCARD_TxCpltCallback can be implemented in the user file.
1520 * @brief Rx Transfer completed callback.
1521 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1522 * the configuration information for the specified SMARTCARD module.
1523 * @retval None
1525 __weak void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsmartcard)
1527 /* Prevent unused argument(s) compilation warning */
1528 UNUSED(hsmartcard);
1530 /* NOTE : This function should not be modified, when the callback is needed,
1531 the HAL_SMARTCARD_RxCpltCallback can be implemented in the user file.
1536 * @brief SMARTCARD error callback.
1537 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1538 * the configuration information for the specified SMARTCARD module.
1539 * @retval None
1541 __weak void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsmartcard)
1543 /* Prevent unused argument(s) compilation warning */
1544 UNUSED(hsmartcard);
1546 /* NOTE : This function should not be modified, when the callback is needed,
1547 the HAL_SMARTCARD_ErrorCallback can be implemented in the user file.
1552 * @brief SMARTCARD Abort Complete callback.
1553 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1554 * the configuration information for the specified SMARTCARD module.
1555 * @retval None
1557 __weak void HAL_SMARTCARD_AbortCpltCallback (SMARTCARD_HandleTypeDef *hsmartcard)
1559 /* Prevent unused argument(s) compilation warning */
1560 UNUSED(hsmartcard);
1562 /* NOTE : This function should not be modified, when the callback is needed,
1563 the HAL_SMARTCARD_AbortCpltCallback can be implemented in the user file.
1568 * @brief SMARTCARD Abort Complete callback.
1569 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1570 * the configuration information for the specified SMARTCARD module.
1571 * @retval None
1573 __weak void HAL_SMARTCARD_AbortTransmitCpltCallback (SMARTCARD_HandleTypeDef *hsmartcard)
1575 /* Prevent unused argument(s) compilation warning */
1576 UNUSED(hsmartcard);
1578 /* NOTE : This function should not be modified, when the callback is needed,
1579 the HAL_SMARTCARD_AbortTransmitCpltCallback can be implemented in the user file.
1584 * @brief SMARTCARD Abort Receive Complete callback.
1585 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1586 * the configuration information for the specified SMARTCARD module.
1587 * @retval None
1589 __weak void HAL_SMARTCARD_AbortReceiveCpltCallback (SMARTCARD_HandleTypeDef *hsmartcard)
1591 /* Prevent unused argument(s) compilation warning */
1592 UNUSED(hsmartcard);
1594 /* NOTE : This function should not be modified, when the callback is needed,
1595 the HAL_SMARTCARD_AbortReceiveCpltCallback can be implemented in the user file.
1600 * @}
1603 /** @defgroup SMARTCARD_Exported_Functions_Group3 Peripheral State and Errors functions
1604 * @brief SMARTCARD State and Errors functions
1606 @verbatim
1607 ==============================================================================
1608 ##### Peripheral State and Errors functions #####
1609 ==============================================================================
1610 [..]
1611 This subsection provides a set of functions allowing to return the State of SmartCard
1612 handle and also return Peripheral Errors occurred during communication process
1613 (+) HAL_SMARTCARD_GetState() API can be helpful to check in run-time the state
1614 of the SMARTCARD peripheral.
1615 (+) HAL_SMARTCARD_GetError() checks in run-time errors that could occur during
1616 communication.
1618 @endverbatim
1619 * @{
1623 * @brief Return the SMARTCARD handle state.
1624 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1625 * the configuration information for the specified SMARTCARD module.
1626 * @retval SMARTCARD handle state
1628 HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsmartcard)
1630 /* Return SMARTCARD handle state */
1631 uint32_t temp1= 0x00U, temp2 = 0x00U;
1632 temp1 = hsmartcard->gState;
1633 temp2 = hsmartcard->RxState;
1635 return (HAL_SMARTCARD_StateTypeDef)(temp1 | temp2);
1639 * @brief Return the SMARTCARD handle error code.
1640 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1641 * the configuration information for the specified SMARTCARD module.
1642 * @retval SMARTCARD handle Error Code
1644 uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsmartcard)
1646 return hsmartcard->ErrorCode;
1650 * @}
1654 * @}
1657 /** @defgroup SMARTCARD_Private_Functions SMARTCARD Private Functions
1658 * @{
1662 * @brief Configure the SMARTCARD associated USART peripheral.
1663 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1664 * the configuration information for the specified SMARTCARD module.
1665 * @retval HAL status
1667 static HAL_StatusTypeDef SMARTCARD_SetConfig(SMARTCARD_HandleTypeDef *hsmartcard)
1669 uint32_t tmpreg = 0x00000000U;
1670 SMARTCARD_ClockSourceTypeDef clocksource = SMARTCARD_CLOCKSOURCE_UNDEFINED;
1671 HAL_StatusTypeDef ret = HAL_OK;
1673 /* Check the parameters */
1674 assert_param(IS_SMARTCARD_INSTANCE(hsmartcard->Instance));
1675 assert_param(IS_SMARTCARD_BAUDRATE(hsmartcard->Init.BaudRate));
1676 assert_param(IS_SMARTCARD_WORD_LENGTH(hsmartcard->Init.WordLength));
1677 assert_param(IS_SMARTCARD_STOPBITS(hsmartcard->Init.StopBits));
1678 assert_param(IS_SMARTCARD_PARITY(hsmartcard->Init.Parity));
1679 assert_param(IS_SMARTCARD_MODE(hsmartcard->Init.Mode));
1680 assert_param(IS_SMARTCARD_POLARITY(hsmartcard->Init.CLKPolarity));
1681 assert_param(IS_SMARTCARD_PHASE(hsmartcard->Init.CLKPhase));
1682 assert_param(IS_SMARTCARD_LASTBIT(hsmartcard->Init.CLKLastBit));
1683 assert_param(IS_SMARTCARD_ONE_BIT_SAMPLE(hsmartcard->Init.OneBitSampling));
1684 assert_param(IS_SMARTCARD_NACK(hsmartcard->Init.NACKEnable));
1685 assert_param(IS_SMARTCARD_TIMEOUT(hsmartcard->Init.TimeOutEnable));
1686 assert_param(IS_SMARTCARD_AUTORETRY_COUNT(hsmartcard->Init.AutoRetryCount));
1688 /*-------------------------- USART CR1 Configuration -----------------------*/
1689 /* In SmartCard mode, M and PCE are forced to 1 (8 bits + parity).
1690 * Oversampling is forced to 16 (OVER8 = 0).
1691 * Configure the Parity and Mode:
1692 * set PS bit according to hsmartcard->Init.Parity value
1693 * set TE and RE bits according to hsmartcard->Init.Mode value */
1694 tmpreg = (uint32_t) hsmartcard->Init.Parity | hsmartcard->Init.Mode;
1695 tmpreg |= (uint32_t) hsmartcard->Init.WordLength;
1696 MODIFY_REG(hsmartcard->Instance->CR1, USART_CR1_FIELDS, tmpreg);
1698 /*-------------------------- USART CR2 Configuration -----------------------*/
1699 tmpreg = hsmartcard->Init.StopBits;
1700 /* Synchronous mode is activated by default */
1701 tmpreg |= (uint32_t) USART_CR2_CLKEN | hsmartcard->Init.CLKPolarity;
1702 tmpreg |= (uint32_t) hsmartcard->Init.CLKPhase | hsmartcard->Init.CLKLastBit;
1703 tmpreg |= (uint32_t) hsmartcard->Init.TimeOutEnable;
1704 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_FIELDS, tmpreg);
1706 /*-------------------------- USART CR3 Configuration -----------------------*/
1707 /* Configure
1708 * - one-bit sampling method versus three samples' majority rule
1709 * according to hsmartcard->Init.OneBitSampling
1710 * - NACK transmission in case of parity error according
1711 * to hsmartcard->Init.NACKEnable
1712 * - autoretry counter according to hsmartcard->Init.AutoRetryCount */
1713 tmpreg = (uint32_t) hsmartcard->Init.OneBitSampling | hsmartcard->Init.NACKEnable;
1714 tmpreg |= ((uint32_t)hsmartcard->Init.AutoRetryCount << SMARTCARD_CR3_SCARCNT_LSB_POS);
1715 MODIFY_REG(hsmartcard->Instance-> CR3,USART_CR3_FIELDS, tmpreg);
1717 /*-------------------------- USART GTPR Configuration ----------------------*/
1718 tmpreg = (hsmartcard->Init.Prescaler | ((uint32_t)hsmartcard->Init.GuardTime << SMARTCARD_GTPR_GT_LSB_POS));
1719 MODIFY_REG(hsmartcard->Instance->GTPR, (USART_GTPR_GT|USART_GTPR_PSC), tmpreg);
1721 /*-------------------------- USART RTOR Configuration ----------------------*/
1722 tmpreg = ((uint32_t)hsmartcard->Init.BlockLength << SMARTCARD_RTOR_BLEN_LSB_POS);
1723 if (hsmartcard->Init.TimeOutEnable == SMARTCARD_TIMEOUT_ENABLE)
1725 assert_param(IS_SMARTCARD_TIMEOUT_VALUE(hsmartcard->Init.TimeOutValue));
1726 tmpreg |= (uint32_t) hsmartcard->Init.TimeOutValue;
1728 MODIFY_REG(hsmartcard->Instance->RTOR, (USART_RTOR_RTO|USART_RTOR_BLEN), tmpreg);
1730 /*-------------------------- USART BRR Configuration -----------------------*/
1731 SMARTCARD_GETCLOCKSOURCE(hsmartcard, clocksource);
1732 switch (clocksource)
1734 case SMARTCARD_CLOCKSOURCE_PCLK1:
1735 hsmartcard->Instance->BRR = (uint16_t)((HAL_RCC_GetPCLK1Freq() + (hsmartcard->Init.BaudRate/2U)) / hsmartcard->Init.BaudRate);
1736 break;
1737 case SMARTCARD_CLOCKSOURCE_PCLK2:
1738 hsmartcard->Instance->BRR = (uint16_t)((HAL_RCC_GetPCLK2Freq() + (hsmartcard->Init.BaudRate/2U)) / hsmartcard->Init.BaudRate);
1739 break;
1740 case SMARTCARD_CLOCKSOURCE_HSI:
1741 hsmartcard->Instance->BRR = (uint16_t)((HSI_VALUE + (hsmartcard->Init.BaudRate/2U)) / hsmartcard->Init.BaudRate);
1742 break;
1743 case SMARTCARD_CLOCKSOURCE_SYSCLK:
1744 hsmartcard->Instance->BRR = (uint16_t)((HAL_RCC_GetSysClockFreq() + (hsmartcard->Init.BaudRate/2U)) / hsmartcard->Init.BaudRate);
1745 break;
1746 case SMARTCARD_CLOCKSOURCE_LSE:
1747 hsmartcard->Instance->BRR = (uint16_t)((LSE_VALUE + (hsmartcard->Init.BaudRate/2U)) / hsmartcard->Init.BaudRate);
1748 break;
1749 case SMARTCARD_CLOCKSOURCE_UNDEFINED:
1750 default:
1751 ret = HAL_ERROR;
1752 break;
1755 return ret;
1760 * @brief Configure the SMARTCARD associated USART peripheral advanced features.
1761 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1762 * the configuration information for the specified SMARTCARD module.
1763 * @retval None
1765 static void SMARTCARD_AdvFeatureConfig(SMARTCARD_HandleTypeDef *hsmartcard)
1767 /* Check whether the set of advanced features to configure is properly set */
1768 assert_param(IS_SMARTCARD_ADVFEATURE_INIT(hsmartcard->AdvancedInit.AdvFeatureInit));
1770 /* if required, configure TX pin active level inversion */
1771 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_TXINVERT_INIT))
1773 assert_param(IS_SMARTCARD_ADVFEATURE_TXINV(hsmartcard->AdvancedInit.TxPinLevelInvert));
1774 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_TXINV, hsmartcard->AdvancedInit.TxPinLevelInvert);
1777 /* if required, configure RX pin active level inversion */
1778 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_RXINVERT_INIT))
1780 assert_param(IS_SMARTCARD_ADVFEATURE_RXINV(hsmartcard->AdvancedInit.RxPinLevelInvert));
1781 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_RXINV, hsmartcard->AdvancedInit.RxPinLevelInvert);
1784 /* if required, configure data inversion */
1785 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_DATAINVERT_INIT))
1787 assert_param(IS_SMARTCARD_ADVFEATURE_DATAINV(hsmartcard->AdvancedInit.DataInvert));
1788 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_DATAINV, hsmartcard->AdvancedInit.DataInvert);
1791 /* if required, configure RX/TX pins swap */
1792 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_SWAP_INIT))
1794 assert_param(IS_SMARTCARD_ADVFEATURE_SWAP(hsmartcard->AdvancedInit.Swap));
1795 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_SWAP, hsmartcard->AdvancedInit.Swap);
1798 /* if required, configure RX overrun detection disabling */
1799 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_RXOVERRUNDISABLE_INIT))
1801 assert_param(IS_SMARTCARD_OVERRUN(hsmartcard->AdvancedInit.OverrunDisable));
1802 MODIFY_REG(hsmartcard->Instance->CR3, USART_CR3_OVRDIS, hsmartcard->AdvancedInit.OverrunDisable);
1805 /* if required, configure DMA disabling on reception error */
1806 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_DMADISABLEONERROR_INIT))
1808 assert_param(IS_SMARTCARD_ADVFEATURE_DMAONRXERROR(hsmartcard->AdvancedInit.DMADisableonRxError));
1809 MODIFY_REG(hsmartcard->Instance->CR3, USART_CR3_DDRE, hsmartcard->AdvancedInit.DMADisableonRxError);
1812 /* if required, configure MSB first on communication line */
1813 if (HAL_IS_BIT_SET(hsmartcard->AdvancedInit.AdvFeatureInit, SMARTCARD_ADVFEATURE_MSBFIRST_INIT))
1815 assert_param(IS_SMARTCARD_ADVFEATURE_MSBFIRST(hsmartcard->AdvancedInit.MSBFirst));
1816 MODIFY_REG(hsmartcard->Instance->CR2, USART_CR2_MSBFIRST, hsmartcard->AdvancedInit.MSBFirst);
1822 * @brief Check the SMARTCARD Idle State.
1823 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1824 * the configuration information for the specified SMARTCARD module.
1825 * @retval HAL status
1827 static HAL_StatusTypeDef SMARTCARD_CheckIdleState(SMARTCARD_HandleTypeDef *hsmartcard)
1829 uint32_t tickstart = 0U;
1831 /* Initialize the SMARTCARD ErrorCode */
1832 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
1834 /* Init tickstart for timeout managment*/
1835 tickstart = HAL_GetTick();
1837 /* Check if the Transmitter is enabled */
1838 if((hsmartcard->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE)
1840 /* Wait until TEACK flag is set */
1841 if(SMARTCARD_WaitOnFlagUntilTimeout(hsmartcard, USART_ISR_TEACK, RESET, tickstart, SMARTCARD_TEACK_REACK_TIMEOUT) != HAL_OK)
1843 /* Timeout occurred */
1844 return HAL_TIMEOUT;
1848 /* Check if the Receiver is enabled */
1849 if((hsmartcard->Instance->CR1 & USART_CR1_RE) == USART_CR1_RE)
1851 /* Wait until REACK flag is set */
1852 if(SMARTCARD_WaitOnFlagUntilTimeout(hsmartcard, USART_ISR_REACK, RESET, tickstart, SMARTCARD_TEACK_REACK_TIMEOUT) != HAL_OK)
1854 /* Timeout occurred */
1855 return HAL_TIMEOUT;
1859 /* Initialize the SMARTCARD states */
1860 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1861 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1863 /* Process Unlocked */
1864 __HAL_UNLOCK(hsmartcard);
1866 return HAL_OK;
1870 * @brief Handle SMARTCARD Communication Timeout.
1871 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1872 * the configuration information for the specified SMARTCARD module.
1873 * @param Flag Specifies the SMARTCARD flag to check.
1874 * @param Status The new Flag status (SET or RESET).
1875 * @param Tickstart Tick start value
1876 * @param Timeout Timeout duration.
1877 * @retval HAL status
1879 static HAL_StatusTypeDef SMARTCARD_WaitOnFlagUntilTimeout(SMARTCARD_HandleTypeDef *hsmartcard, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout)
1881 /* Wait until flag is set */
1882 while((__HAL_SMARTCARD_GET_FLAG(hsmartcard, Flag) ? SET : RESET) == Status)
1884 /* Check for the Timeout */
1885 if(Timeout != HAL_MAX_DELAY)
1887 if((Timeout == 0U) || ((HAL_GetTick()-Tickstart) > Timeout))
1889 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
1890 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE));
1891 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1893 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1894 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1896 /* Process Unlocked */
1897 __HAL_UNLOCK(hsmartcard);
1898 return HAL_TIMEOUT;
1902 return HAL_OK;
1907 * @brief End ongoing Tx transfer on SMARTCARD peripheral (following error detection or Transmit completion).
1908 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1909 * the configuration information for the specified SMARTCARD module.
1910 * @retval None
1912 static void SMARTCARD_EndTxTransfer(SMARTCARD_HandleTypeDef *hsmartcard)
1914 /* Disable TXEIE, TCIE and ERR (Frame error, noise error, overrun error) interrupts */
1915 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1916 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1918 /* At end of Tx process, restore hsmartcard->gState to Ready */
1919 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
1924 * @brief End ongoing Rx transfer on UART peripheral (following error detection or Reception completion).
1925 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
1926 * the configuration information for the specified SMARTCARD module.
1927 * @retval None
1929 static void SMARTCARD_EndRxTransfer(SMARTCARD_HandleTypeDef *hsmartcard)
1931 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1932 CLEAR_BIT(hsmartcard->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1933 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1935 /* At end of Rx process, restore hsmartcard->RxState to Ready */
1936 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1941 * @brief DMA SMARTCARD transmit process complete callback.
1942 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1943 * the configuration information for the specified DMA module.
1944 * @retval None
1946 static void SMARTCARD_DMATransmitCplt(DMA_HandleTypeDef *hdma)
1948 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef*)(hdma->Parent);
1949 hsmartcard->TxXferCount = 0U;
1951 /* Disable the DMA transfer for transmit request by resetting the DMAT bit
1952 in the SMARTCARD associated USART CR3 register */
1953 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAT);
1955 /* Enable the SMARTCARD Transmit Complete Interrupt */
1956 __HAL_SMARTCARD_ENABLE_IT(hsmartcard, SMARTCARD_IT_TC);
1960 * @brief DMA SMARTCARD receive process complete callback.
1961 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1962 * the configuration information for the specified DMA module.
1963 * @retval None
1965 static void SMARTCARD_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
1967 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef*)(hdma->Parent);
1968 hsmartcard->RxXferCount = 0U;
1970 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
1971 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_PEIE);
1972 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
1974 /* Disable the DMA transfer for the receiver request by resetting the DMAR bit
1975 in the SMARTCARD associated USART CR3 register */
1976 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_DMAR);
1978 /* At end of Rx process, restore hsmartcard->RxState to Ready */
1979 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
1981 HAL_SMARTCARD_RxCpltCallback(hsmartcard);
1985 * @brief DMA SMARTCARD communication error callback.
1986 * @param hdma Pointer to a DMA_HandleTypeDef structure that contains
1987 * the configuration information for the specified DMA module.
1988 * @retval None
1990 static void SMARTCARD_DMAError(DMA_HandleTypeDef *hdma)
1992 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef*)(hdma->Parent);
1994 /* Stop SMARTCARD DMA Tx request if ongoing */
1995 if ( (hsmartcard->gState == HAL_SMARTCARD_STATE_BUSY_TX)
1996 &&(HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAT)) )
1998 hsmartcard->TxXferCount = 0U;
1999 SMARTCARD_EndTxTransfer(hsmartcard);
2002 /* Stop SMARTCARD DMA Rx request if ongoing */
2003 if ( (hsmartcard->RxState == HAL_SMARTCARD_STATE_BUSY_RX)
2004 &&(HAL_IS_BIT_SET(hsmartcard->Instance->CR3, USART_CR3_DMAR)) )
2006 hsmartcard->RxXferCount = 0U;
2007 SMARTCARD_EndRxTransfer(hsmartcard);
2010 hsmartcard->ErrorCode |= HAL_SMARTCARD_ERROR_DMA;
2011 HAL_SMARTCARD_ErrorCallback(hsmartcard);
2015 * @brief DMA SMARTCARD communication abort callback, when initiated by HAL services on Error
2016 * (To be called at end of DMA Abort procedure following error occurrence).
2017 * @param hdma DMA handle.
2018 * @retval None
2020 static void SMARTCARD_DMAAbortOnError(DMA_HandleTypeDef *hdma)
2022 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef*)(hdma->Parent);
2023 hsmartcard->RxXferCount = 0U;
2024 hsmartcard->TxXferCount = 0U;
2026 HAL_SMARTCARD_ErrorCallback(hsmartcard);
2030 * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user
2031 * (To be called at end of DMA Tx Abort procedure following user abort request).
2032 * @note When this callback is executed, User Abort complete call back is called only if no
2033 * Abort still ongoing for Rx DMA Handle.
2034 * @param hdma DMA handle.
2035 * @retval None
2037 static void SMARTCARD_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
2039 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef* )(hdma->Parent);
2041 hsmartcard->hdmatx->XferAbortCallback = NULL;
2043 /* Check if an Abort process is still ongoing */
2044 if(hsmartcard->hdmarx != NULL)
2046 if(hsmartcard->hdmarx->XferAbortCallback != NULL)
2048 return;
2052 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2053 hsmartcard->TxXferCount = 0U;
2054 hsmartcard->RxXferCount = 0U;
2056 /* Reset errorCode */
2057 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
2059 /* Clear the Error flags in the ICR register */
2060 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
2062 /* Restore hsmartcard->gState and hsmartcard->RxState to Ready */
2063 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
2064 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
2066 /* Call user Abort complete callback */
2067 HAL_SMARTCARD_AbortCpltCallback(hsmartcard);
2072 * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user
2073 * (To be called at end of DMA Rx Abort procedure following user abort request).
2074 * @note When this callback is executed, User Abort complete call back is called only if no
2075 * Abort still ongoing for Tx DMA Handle.
2076 * @param hdma DMA handle.
2077 * @retval None
2079 static void SMARTCARD_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
2081 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef* )(hdma->Parent);
2083 hsmartcard->hdmarx->XferAbortCallback = NULL;
2085 /* Check if an Abort process is still ongoing */
2086 if(hsmartcard->hdmatx != NULL)
2088 if(hsmartcard->hdmatx->XferAbortCallback != NULL)
2090 return;
2094 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
2095 hsmartcard->TxXferCount = 0U;
2096 hsmartcard->RxXferCount = 0U;
2098 /* Reset errorCode */
2099 hsmartcard->ErrorCode = HAL_SMARTCARD_ERROR_NONE;
2101 /* Clear the Error flags in the ICR register */
2102 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
2104 /* Restore hsmartcard->gState and hsmartcard->RxState to Ready */
2105 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
2106 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
2108 /* Call user Abort complete callback */
2109 HAL_SMARTCARD_AbortCpltCallback(hsmartcard);
2114 * @brief DMA SMARTCARD Tx communication abort callback, when initiated by user by a call to
2115 * HAL_SMARTCARD_AbortTransmit_IT API (Abort only Tx transfer)
2116 * (This callback is executed at end of DMA Tx Abort procedure following user abort request,
2117 * and leads to user Tx Abort Complete callback execution).
2118 * @param hdma DMA handle.
2119 * @retval None
2121 static void SMARTCARD_DMATxOnlyAbortCallback(DMA_HandleTypeDef *hdma)
2123 SMARTCARD_HandleTypeDef* hsmartcard = (SMARTCARD_HandleTypeDef*)(hdma->Parent);
2125 hsmartcard->TxXferCount = 0U;
2127 /* Clear the Error flags in the ICR register */
2128 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_FEF);
2130 /* Restore hsmartcard->gState to Ready */
2131 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
2133 /* Call user Abort complete callback */
2134 HAL_SMARTCARD_AbortTransmitCpltCallback(hsmartcard);
2138 * @brief DMA SMARTCARD Rx communication abort callback, when initiated by user by a call to
2139 * HAL_SMARTCARD_AbortReceive_IT API (Abort only Rx transfer)
2140 * (This callback is executed at end of DMA Rx Abort procedure following user abort request,
2141 * and leads to user Rx Abort Complete callback execution).
2142 * @param hdma DMA handle.
2143 * @retval None
2145 static void SMARTCARD_DMARxOnlyAbortCallback(DMA_HandleTypeDef *hdma)
2147 SMARTCARD_HandleTypeDef* hsmartcard = ( SMARTCARD_HandleTypeDef* )(hdma->Parent);
2149 hsmartcard->RxXferCount = 0U;
2151 /* Clear the Error flags in the ICR register */
2152 __HAL_SMARTCARD_CLEAR_FLAG(hsmartcard, SMARTCARD_CLEAR_OREF | SMARTCARD_CLEAR_NEF | SMARTCARD_CLEAR_PEF | SMARTCARD_CLEAR_FEF | SMARTCARD_CLEAR_RTOF | SMARTCARD_CLEAR_EOBF);
2154 /* Restore hsmartcard->RxState to Ready */
2155 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
2157 /* Call user Abort complete callback */
2158 HAL_SMARTCARD_AbortReceiveCpltCallback(hsmartcard);
2162 * @brief Send an amount of data in non-blocking mode.
2163 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
2164 * the configuration information for the specified SMARTCARD module.
2165 * Function called under interruption only, once
2166 * interruptions have been enabled by HAL_SMARTCARD_Transmit_IT()
2167 * @retval HAL status
2169 static HAL_StatusTypeDef SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsmartcard)
2171 /* Check that a Tx process is ongoing */
2172 if (hsmartcard->gState == HAL_SMARTCARD_STATE_BUSY_TX)
2174 if(hsmartcard->TxXferCount == 0U)
2176 /* Disable the SMARTCARD Transmit Data Register Empty Interrupt */
2177 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_TXEIE);
2179 /* Enable the SMARTCARD Transmit Complete Interrupt */
2180 __HAL_SMARTCARD_ENABLE_IT(hsmartcard, SMARTCARD_IT_TC);
2182 return HAL_OK;
2184 else
2186 hsmartcard->Instance->TDR = (*hsmartcard->pTxBuffPtr++ & (uint8_t)0xFFU);
2187 hsmartcard->TxXferCount--;
2189 return HAL_OK;
2192 else
2194 return HAL_BUSY;
2199 * @brief Wrap up transmission in non-blocking mode.
2200 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
2201 * the configuration information for the specified SMARTCARD module.
2202 * @retval HAL status
2204 static HAL_StatusTypeDef SMARTCARD_EndTransmit_IT(SMARTCARD_HandleTypeDef *hsmartcard)
2206 /* Disable the SMARTCARD Transmit Complete Interrupt */
2207 __HAL_SMARTCARD_DISABLE_IT(hsmartcard, SMARTCARD_IT_TC);
2209 /* Check if a receive process is ongoing or not. If not disable ERR IT */
2210 if(hsmartcard->RxState == HAL_SMARTCARD_STATE_READY)
2212 /* Disable the SMARTCARD Error Interrupt: (Frame error) */
2213 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
2216 /* Re-enable Rx at end of transmission if initial mode is Rx/Tx */
2217 if(hsmartcard->Init.Mode == SMARTCARD_MODE_TX_RX)
2219 /* Disable the Peripheral first to update modes */
2220 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
2221 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_RE);
2222 /* Enable the Peripheral */
2223 SET_BIT(hsmartcard->Instance->CR1, USART_CR1_UE);
2226 /* Tx process is ended, restore hsmartcard->gState to Ready */
2227 hsmartcard->gState = HAL_SMARTCARD_STATE_READY;
2229 HAL_SMARTCARD_TxCpltCallback(hsmartcard);
2231 return HAL_OK;
2235 * @brief Receive an amount of data in non-blocking mode.
2236 * @param hsmartcard Pointer to a SMARTCARD_HandleTypeDef structure that contains
2237 * the configuration information for the specified SMARTCARD module.
2238 * Function called under interruption only, once
2239 * interruptions have been enabled by HAL_SMARTCARD_Receive_IT().
2240 * @retval HAL status
2242 static HAL_StatusTypeDef SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsmartcard)
2244 /* Check that a Rx process is ongoing */
2245 if (hsmartcard->RxState == HAL_SMARTCARD_STATE_BUSY_RX)
2247 *hsmartcard->pRxBuffPtr++ = (uint8_t)(hsmartcard->Instance->RDR & (uint8_t)0xFF);
2249 if(--hsmartcard->RxXferCount == 0U)
2251 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_RXNEIE);
2253 /* Check if a transmit process is ongoing or not. If not disable ERR IT */
2254 if(hsmartcard->gState == HAL_SMARTCARD_STATE_READY)
2256 /* Disable the SMARTCARD Error Interrupt: (Frame error, noise error, overrun error) */
2257 CLEAR_BIT(hsmartcard->Instance->CR3, USART_CR3_EIE);
2260 /* Disable the SMARTCARD Parity Error Interrupt */
2261 CLEAR_BIT(hsmartcard->Instance->CR1, USART_CR1_PEIE);
2263 hsmartcard->RxState = HAL_SMARTCARD_STATE_READY;
2265 HAL_SMARTCARD_RxCpltCallback(hsmartcard);
2267 return HAL_OK;
2270 return HAL_OK;
2272 else
2274 /* Clear RXNE interrupt flag */
2275 __HAL_SMARTCARD_SEND_REQ(hsmartcard, SMARTCARD_RXDATA_FLUSH_REQUEST);
2277 return HAL_BUSY;
2282 * @}
2285 #endif /* HAL_SMARTCARD_MODULE_ENABLED */
2287 * @}
2291 * @}
2294 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/