Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Src / stm32f3xx_hal_usart.c
blob0a1181ff1997c7bd5010d8f7f11e986a84d902cf
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_hal_usart.c
4 * @author MCD Application Team
5 * @brief USART HAL module driver.
6 * This file provides firmware functions to manage the following
7 * functionalities of the Universal Synchronous Asynchronous Receiver Transmitter
8 * Peripheral (USART).
9 * + Initialization and de-initialization functions
10 * + IO operation functions
11 * + Peripheral Control functions
12 * + Peripheral State and Error functions
14 @verbatim
15 ===============================================================================
16 ##### How to use this driver #####
17 ===============================================================================
18 [..]
19 The USART HAL driver can be used as follows:
21 (#) Declare a USART_HandleTypeDef handle structure (eg. USART_HandleTypeDef husart).
22 (#) Initialize the USART low level resources by implementing the HAL_USART_MspInit() API:
23 (++) Enable the USARTx interface clock.
24 (++) USART pins configuration:
25 (+++) Enable the clock for the USART GPIOs.
26 (+++) Configure these USART pins as alternate function pull-up.
27 (++) NVIC configuration if you need to use interrupt process (HAL_USART_Transmit_IT(),
28 HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs):
29 (+++) Configure the USARTx interrupt priority.
30 (+++) Enable the NVIC USART IRQ handle.
31 (++) USART interrupts handling:
32 -@@- The specific USART interrupts (Transmission complete interrupt,
33 RXNE interrupt and Error Interrupts) will be managed using the macros
34 __HAL_USART_ENABLE_IT() and __HAL_USART_DISABLE_IT() inside the transmit and receive process.
35 (++) DMA Configuration if you need to use DMA process (HAL_USART_Transmit_DMA()
36 HAL_USART_Receive_DMA() and HAL_USART_TransmitReceive_DMA() APIs):
37 (+++) Declare a DMA handle structure for the Tx/Rx channel.
38 (+++) Enable the DMAx interface clock.
39 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
40 (+++) Configure the DMA Tx/Rx channel.
41 (+++) Associate the initialized DMA handle to the USART DMA Tx/Rx handle.
42 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx channel.
44 (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware
45 flow control and Mode (Receiver/Transmitter) in the husart handle Init structure.
47 (#) Initialize the USART registers by calling the HAL_USART_Init() API:
48 (++) This API configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc)
49 by calling the customized HAL_USART_MspInit(&husart) API.
51 (#) Three operation modes are available within this driver :
53 *** Polling mode IO operation ***
54 =================================
55 [..]
56 (+) Send an amount of data in blocking mode using HAL_USART_Transmit()
57 (+) Receive an amount of data in blocking mode using HAL_USART_Receive()
59 *** Interrupt mode IO operation ***
60 ===================================
61 [..]
62 (+) Send an amount of data in non blocking mode using HAL_USART_Transmit_IT()
63 (+) At transmission end of half transfer HAL_USART_TxHalfCpltCallback is executed and user can
64 add his own code by customization of function pointer HAL_USART_TxHalfCpltCallback
65 (+) At transmission end of transfer HAL_USART_TxCpltCallback is executed and user can
66 add his own code by customization of function pointer HAL_USART_TxCpltCallback
67 (+) Receive an amount of data in non blocking mode using HAL_USART_Receive_IT()
68 (+) At reception end of half transfer HAL_USART_RxHalfCpltCallback is executed and user can
69 add his own code by customization of function pointer HAL_USART_RxHalfCpltCallback
70 (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can
71 add his own code by customization of function pointer HAL_USART_RxCpltCallback
72 (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can
73 add his own code by customization of function pointer HAL_USART_ErrorCallback
75 *** DMA mode IO operation ***
76 ==============================
77 [..]
78 (+) Send an amount of data in non blocking mode (DMA) using HAL_USART_Transmit_DMA()
79 (+) At transmission end of half transfer HAL_USART_TxHalfCpltCallback is executed and user can
80 add his own code by customization of function pointer HAL_USART_TxHalfCpltCallback
81 (+) At transmission end of transfer HAL_USART_TxCpltCallback is executed and user can
82 add his own code by customization of function pointer HAL_USART_TxCpltCallback
83 (+) Receive an amount of data in non blocking mode (DMA) using HAL_USART_Receive_DMA()
84 (+) At reception end of half transfer HAL_USART_RxHalfCpltCallback is executed and user can
85 add his own code by customization of function pointer HAL_USART_RxHalfCpltCallback
86 (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can
87 add his own code by customization of function pointer HAL_USART_RxCpltCallback
88 (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can
89 add his own code by customization of function pointer HAL_USART_ErrorCallback
90 (+) Pause the DMA Transfer using HAL_USART_DMAPause()
91 (+) Resume the DMA Transfer using HAL_USART_DMAResume()
92 (+) Stop the DMA Transfer using HAL_USART_DMAStop()
94 *** USART HAL driver macros list ***
95 =============================================
96 [..]
97 Below the list of most used macros in USART HAL driver.
99 (+) __HAL_USART_ENABLE: Enable the USART peripheral
100 (+) __HAL_USART_DISABLE: Disable the USART peripheral
101 (+) __HAL_USART_GET_FLAG : Check whether the specified USART flag is set or not
102 (+) __HAL_USART_CLEAR_FLAG : Clear the specified USART pending flag
103 (+) __HAL_USART_ENABLE_IT: Enable the specified USART interrupt
104 (+) __HAL_USART_DISABLE_IT: Disable the specified USART interrupt
106 [..]
107 (@) You can refer to the USART HAL driver header file for more useful macros
108 [..]
109 (@) To configure and enable/disable the USART to wake up the MCU from stop mode, resort to UART API's
110 HAL_UARTEx_StopModeWakeUpSourceConfig(), HAL_UARTEx_EnableStopMode() and
111 HAL_UARTEx_DisableStopMode() in casting the USART handle to UART type UART_HandleTypeDef.
113 @endverbatim
114 ******************************************************************************
115 * @attention
117 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
119 * Redistribution and use in source and binary forms, with or without modification,
120 * are permitted provided that the following conditions are met:
121 * 1. Redistributions of source code must retain the above copyright notice,
122 * this list of conditions and the following disclaimer.
123 * 2. Redistributions in binary form must reproduce the above copyright notice,
124 * this list of conditions and the following disclaimer in the documentation
125 * and/or other materials provided with the distribution.
126 * 3. Neither the name of STMicroelectronics nor the names of its contributors
127 * may be used to endorse or promote products derived from this software
128 * without specific prior written permission.
130 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
131 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
132 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
133 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
134 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
135 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
136 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
137 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
138 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
139 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
141 ******************************************************************************
144 /* Includes ------------------------------------------------------------------*/
145 #include "stm32f3xx_hal.h"
147 /** @addtogroup STM32F3xx_HAL_Driver
148 * @{
151 /** @defgroup USART USART
152 * @brief USART HAL module driver
153 * @{
156 #ifdef HAL_USART_MODULE_ENABLED
158 /* Private typedef -----------------------------------------------------------*/
159 /* Private define ------------------------------------------------------------*/
160 /** @defgroup USART_Private_Constants USART Private Constants
161 * @{
163 #define USART_DUMMY_DATA ((uint16_t) 0xFFFFU) /*!< USART transmitted dummy data */
164 #define USART_TEACK_REACK_TIMEOUT ( 1000U) /*!< USART TX or RX enable acknowledge time-out value */
165 #define USART_CR1_FIELDS ((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | \
166 USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8)) /*!< USART CR1 fields of parameters set by USART_SetConfig API */
167 #define USART_CR2_FIELDS ((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | \
168 USART_CR2_CLKEN | USART_CR2_LBCL | USART_CR2_STOP)) /*!< USART CR2 fields of parameters set by USART_SetConfig API */
170 * @}
173 /* Private macros ------------------------------------------------------------*/
174 /* Private variables ---------------------------------------------------------*/
175 /* Private function prototypes -----------------------------------------------*/
176 /** @addtogroup USART_Private_Functions
177 * @{
179 static void USART_EndTransfer(USART_HandleTypeDef *husart);
180 static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma);
181 static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
182 static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma);
183 static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
184 static void USART_DMAError(DMA_HandleTypeDef *hdma);
185 static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma);
186 static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma);
187 static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma);
188 static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout);
189 static HAL_StatusTypeDef USART_SetConfig(USART_HandleTypeDef *husart);
190 static HAL_StatusTypeDef USART_CheckIdleState(USART_HandleTypeDef *husart);
191 static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart);
192 static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart);
193 static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart);
194 static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart);
196 * @}
199 /* Exported functions --------------------------------------------------------*/
201 /** @defgroup USART_Exported_Functions USART Exported Functions
202 * @{
205 /** @defgroup USART_Exported_Functions_Group1 Initialization and de-initialization functions
206 * @brief Initialization and Configuration functions
208 @verbatim
209 ===============================================================================
210 ##### Initialization and Configuration functions #####
211 ===============================================================================
212 [..]
213 This subsection provides a set of functions allowing to initialize the USART
214 in asynchronous and in synchronous modes.
215 (+) For the asynchronous mode only these parameters can be configured:
216 (++) Baud Rate
217 (++) Word Length
218 (++) Stop Bit
219 (++) Parity
220 (++) USART polarity
221 (++) USART phase
222 (++) USART LastBit
223 (++) Receiver/transmitter modes
225 [..]
226 The HAL_USART_Init() function follows the USART synchronous configuration
227 procedure (details for the procedure are available in reference manual).
229 @endverbatim
230 * @{
234 Additional Table: If the parity is enabled, then the MSB bit of the data written
235 in the data register is transmitted but is changed by the parity bit.
236 According to device capability (support or not of 7-bit word length),
237 frame length is either defined by the M bit (8-bits or 9-bits)
238 or by the M1 and M0 bits (7-bit, 8-bit or 9-bit).
239 Possible USART frame formats are as listed in the following table:
241 Table 1. USART frame format.
242 +-----------------------------------------------------------------------+
243 | M bit | PCE bit | USART frame |
244 |-------------------|-----------|---------------------------------------|
245 | 0 | 0 | | SB | 8-bit data | STB | |
246 |-------------------|-----------|---------------------------------------|
247 | 0 | 1 | | SB | 7-bit data | PB | STB | |
248 |-------------------|-----------|---------------------------------------|
249 | 1 | 0 | | SB | 9-bit data | STB | |
250 |-------------------|-----------|---------------------------------------|
251 | 1 | 1 | | SB | 8-bit data | PB | STB | |
252 +-----------------------------------------------------------------------+
253 | M1 bit | M0 bit | PCE bit | USART frame |
254 |---------|---------|-----------|---------------------------------------|
255 | 0 | 0 | 0 | | SB | 8 bit data | STB | |
256 |---------|---------|-----------|---------------------------------------|
257 | 0 | 0 | 1 | | SB | 7 bit data | PB | STB | |
258 |---------|---------|-----------|---------------------------------------|
259 | 0 | 1 | 0 | | SB | 9 bit data | STB | |
260 |---------|---------|-----------|---------------------------------------|
261 | 0 | 1 | 1 | | SB | 8 bit data | PB | STB | |
262 |---------|---------|-----------|---------------------------------------|
263 | 1 | 0 | 0 | | SB | 7 bit data | STB | |
264 |---------|---------|-----------|---------------------------------------|
265 | 1 | 0 | 1 | | SB | 6 bit data | PB | STB | |
266 +-----------------------------------------------------------------------+
271 * @brief Initialize the USART mode according to the specified
272 * parameters in the USART_InitTypeDef and initialize the associated handle.
273 * @param husart USART handle.
274 * @retval HAL status
276 HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart)
278 /* Check the USART handle allocation */
279 if(husart == NULL)
281 return HAL_ERROR;
284 /* Check the parameters */
285 assert_param(IS_USART_INSTANCE(husart->Instance));
287 if(husart->State == HAL_USART_STATE_RESET)
289 /* Allocate lock resource and initialize it */
290 husart->Lock = HAL_UNLOCKED;
292 /* Init the low level hardware : GPIO, CLOCK */
293 HAL_USART_MspInit(husart);
296 husart->State = HAL_USART_STATE_BUSY;
298 /* Disable the Peripheral */
299 __HAL_USART_DISABLE(husart);
301 /* Set the Usart Communication parameters */
302 if (USART_SetConfig(husart) == HAL_ERROR)
304 return HAL_ERROR;
307 /* In Synchronous mode, the following bits must be kept cleared:
308 - LINEN bit in the USART_CR2 register
309 - HDSEL, SCEN and IREN bits in the USART_CR3 register.*/
310 husart->Instance->CR2 &= ~USART_CR2_LINEN;
311 husart->Instance->CR3 &= ~(USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN);
313 /* Enable the Peripheral */
314 __HAL_USART_ENABLE(husart);
316 /* TEACK and/or REACK to check before moving husart->State to Ready */
317 return (USART_CheckIdleState(husart));
321 * @brief DeInitialize the USART peripheral.
322 * @param husart USART handle.
323 * @retval HAL status
325 HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart)
327 /* Check the USART handle allocation */
328 if(husart == NULL)
330 return HAL_ERROR;
333 /* Check the parameters */
334 assert_param(IS_USART_INSTANCE(husart->Instance));
336 husart->State = HAL_USART_STATE_BUSY;
338 husart->Instance->CR1 = 0x0U;
339 husart->Instance->CR2 = 0x0U;
340 husart->Instance->CR3 = 0x0U;
342 /* DeInit the low level hardware */
343 HAL_USART_MspDeInit(husart);
345 husart->ErrorCode = HAL_USART_ERROR_NONE;
346 husart->State = HAL_USART_STATE_RESET;
348 /* Process Unlock */
349 __HAL_UNLOCK(husart);
351 return HAL_OK;
355 * @brief Initialize the USART MSP.
356 * @param husart USART handle.
357 * @retval None
359 __weak void HAL_USART_MspInit(USART_HandleTypeDef *husart)
361 /* Prevent unused argument(s) compilation warning */
362 UNUSED(husart);
364 /* NOTE : This function should not be modified, when the callback is needed,
365 the HAL_USART_MspInit can be implemented in the user file
370 * @brief DeInitialize the USART MSP.
371 * @param husart USART handle.
372 * @retval None
374 __weak void HAL_USART_MspDeInit(USART_HandleTypeDef *husart)
376 /* Prevent unused argument(s) compilation warning */
377 UNUSED(husart);
379 /* NOTE : This function should not be modified, when the callback is needed,
380 the HAL_USART_MspDeInit can be implemented in the user file
385 * @}
388 /** @defgroup USART_Exported_Functions_Group2 IO operation functions
389 * @brief USART Transmit and Receive functions
391 @verbatim
392 ===============================================================================
393 ##### IO operation functions #####
394 ===============================================================================
395 [..] This subsection provides a set of functions allowing to manage the USART synchronous
396 data transfers.
398 [..] The USART supports master mode only: it cannot receive or send data related to an input
399 clock (SCLK is always an output).
401 (#) There are two modes of transfer:
402 (++) Blocking mode: The communication is performed in polling mode.
403 The HAL status of all data processing is returned by the same function
404 after finishing transfer.
405 (++) No-Blocking mode: The communication is performed using Interrupts
406 or DMA, These APIs return the HAL status.
407 The end of the data processing will be indicated through the
408 dedicated USART IRQ when using Interrupt mode or the DMA IRQ when
409 using DMA mode.
410 The HAL_USART_TxCpltCallback(), HAL_USART_RxCpltCallback() and HAL_USART_TxRxCpltCallback() user callbacks
411 will be executed respectively at the end of the transmit or Receive process
412 The HAL_USART_ErrorCallback()user callback will be executed when a communication error is detected
414 (#) Blocking mode APIs are :
415 (++) HAL_USART_Transmit() in simplex mode
416 (++) HAL_USART_Receive() in full duplex receive only
417 (++) HAL_USART_TransmitReceive() in full duplex mode
419 (#) No-Blocking mode APIs with Interrupt are :
420 (++) HAL_USART_Transmit_IT() in simplex mode
421 (++) HAL_USART_Receive_IT() in full duplex receive only
422 (++) HAL_USART_TransmitReceive_IT()in full duplex mode
423 (++) HAL_USART_IRQHandler()
425 (#) No-Blocking mode APIs with DMA are :
426 (++) HAL_USART_Transmit_DMA() in simplex mode
427 (++) HAL_USART_Receive_DMA() in full duplex receive only
428 (++) HAL_USART_TransmitReceive_DMA() in full duplex mode
429 (++) HAL_USART_DMAPause()
430 (++) HAL_USART_DMAResume()
431 (++) HAL_USART_DMAStop()
433 (#) A set of Transfer Complete Callbacks are provided in No-Blocking mode:
434 (++) HAL_USART_TxCpltCallback()
435 (++) HAL_USART_RxCpltCallback()
436 (++) HAL_USART_TxHalfCpltCallback()
437 (++) HAL_USART_RxHalfCpltCallback()
438 (++) HAL_USART_ErrorCallback()
439 (++) HAL_USART_TxRxCpltCallback()
441 (#) Non-Blocking mode transfers could be aborted using Abort API's :
442 (++) HAL_USART_Abort()
443 (++) HAL_USART_Abort_IT()
445 (#) For Abort services based on interrupts (HAL_USART_Abort_IT), a Abort Complete Callbacks is provided:
446 (++) HAL_USART_AbortCpltCallback()
448 (#) In Non-Blocking mode transfers, possible errors are split into 2 categories.
449 Errors are handled as follows :
450 (++) Error is considered as Recoverable and non blocking : Transfer could go till end, but error severity is
451 to be evaluated by user : this concerns Frame Error, Parity Error or Noise Error in Interrupt mode reception .
452 Received character is then retrieved and stored in Rx buffer, Error code is set to allow user to identify error type,
453 and HAL_USART_ErrorCallback() user callback is executed. Transfer is kept ongoing on USART side.
454 If user wants to abort it, Abort services should be called by user.
455 (++) Error is considered as Blocking : Transfer could not be completed properly and is aborted.
456 This concerns Overrun Error In Interrupt mode reception and all errors in DMA mode.
457 Error code is set to allow user to identify error type, and HAL_USART_ErrorCallback() user callback is executed.
459 @endverbatim
460 * @{
464 * @brief Simplex send an amount of data in blocking mode.
465 * @param husart USART handle.
466 * @param pTxData Pointer to data buffer.
467 * @param Size Amount of data to be sent.
468 * @param Timeout Timeout duration.
469 * @retval HAL status
471 HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout)
473 uint16_t* tmp=0U;
474 uint32_t tickstart = 0U;
476 if(husart->State == HAL_USART_STATE_READY)
478 if((pTxData == NULL) || (Size == 0U))
480 return HAL_ERROR;
483 /* Process Locked */
484 __HAL_LOCK(husart);
486 husart->ErrorCode = HAL_USART_ERROR_NONE;
487 husart->State = HAL_USART_STATE_BUSY_TX;
489 /* Init tickstart for timeout managment*/
490 tickstart = HAL_GetTick();
492 husart->TxXferSize = Size;
493 husart->TxXferCount = Size;
495 /* Check the remaining data to be sent */
496 while(husart->TxXferCount > 0U)
498 husart->TxXferCount--;
499 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
501 return HAL_TIMEOUT;
503 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
505 tmp = (uint16_t*) pTxData;
506 husart->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
507 pTxData += 2U;
509 else
511 husart->Instance->TDR = (*pTxData++ & (uint8_t)0xFFU);
515 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
517 return HAL_TIMEOUT;
520 /* At end of Tx process, restore husart->State to Ready */
521 husart->State = HAL_USART_STATE_READY;
523 /* Process Unlocked */
524 __HAL_UNLOCK(husart);
526 return HAL_OK;
528 else
530 return HAL_BUSY;
535 * @brief Receive an amount of data in blocking mode.
536 * @note To receive synchronous data, dummy data are simultaneously transmitted.
537 * @param husart USART handle.
538 * @param pRxData Pointer to data buffer.
539 * @param Size Amount of data to be received.
540 * @param Timeout Timeout duration.
541 * @retval HAL status
543 HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
545 uint16_t* tmp=0U;
546 uint16_t uhMask;
547 uint32_t tickstart = 0U;
549 if(husart->State == HAL_USART_STATE_READY)
551 if((pRxData == NULL) || (Size == 0U))
553 return HAL_ERROR;
556 /* Process Locked */
557 __HAL_LOCK(husart);
559 husart->ErrorCode = HAL_USART_ERROR_NONE;
560 husart->State = HAL_USART_STATE_BUSY_RX;
562 /* Init tickstart for timeout managment*/
563 tickstart = HAL_GetTick();
565 husart->RxXferSize = Size;
566 husart->RxXferCount = Size;
568 /* Computation of USART mask to apply to RDR register */
569 USART_MASK_COMPUTATION(husart);
570 uhMask = husart->Mask;
572 /* as long as data have to be received */
573 while(husart->RxXferCount > 0U)
575 husart->RxXferCount--;
577 /* Wait until TC flag is set to send dummy byte in order to generate the
578 * clock for the slave to send data.
579 * Whatever the frame length (7, 8 or 9-bit long), the same dummy value
580 * can be written for all the cases. */
581 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
583 return HAL_TIMEOUT;
585 husart->Instance->TDR = (USART_DUMMY_DATA & (uint16_t)0x0FFU);
587 /* Wait for RXNE Flag */
588 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
590 return HAL_TIMEOUT;
593 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
595 tmp = (uint16_t*) pRxData ;
596 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
597 pRxData +=2U;
599 else
601 *pRxData++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
605 /* At end of Rx process, restore husart->State to Ready */
606 husart->State = HAL_USART_STATE_READY;
608 /* Process Unlocked */
609 __HAL_UNLOCK(husart);
611 return HAL_OK;
613 else
615 return HAL_BUSY;
620 * @brief Full-Duplex Send and Receive an amount of data in blocking mode.
621 * @param husart USART handle.
622 * @param pTxData pointer to TX data buffer.
623 * @param pRxData pointer to RX data buffer.
624 * @param Size amount of data to be sent (same amount to be received).
625 * @param Timeout Timeout duration.
626 * @retval HAL status
628 HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
630 uint16_t* tmp=0U;
631 uint16_t uhMask;
632 uint32_t tickstart = 0U;
634 if(husart->State == HAL_USART_STATE_READY)
636 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
638 return HAL_ERROR;
641 /* Process Locked */
642 __HAL_LOCK(husart);
644 husart->ErrorCode = HAL_USART_ERROR_NONE;
645 husart->State = HAL_USART_STATE_BUSY_RX;
647 /* Init tickstart for timeout managment*/
648 tickstart = HAL_GetTick();
650 husart->RxXferSize = Size;
651 husart->TxXferSize = Size;
652 husart->TxXferCount = Size;
653 husart->RxXferCount = Size;
655 /* Computation of USART mask to apply to RDR register */
656 USART_MASK_COMPUTATION(husart);
657 uhMask = husart->Mask;
659 /* Check the remain data to be sent */
660 while(husart->TxXferCount > 0U)
662 husart->TxXferCount--;
663 husart->RxXferCount--;
665 /* Wait until TC flag is set to send data */
666 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
668 return HAL_TIMEOUT;
670 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
672 tmp = (uint16_t*) pTxData;
673 husart->Instance->TDR = (*tmp & uhMask);
674 pTxData += 2U;
676 else
678 husart->Instance->TDR = (*pTxData++ & (uint8_t)uhMask);
681 /* Wait for RXNE Flag */
682 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
684 return HAL_TIMEOUT;
687 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
689 tmp = (uint16_t*) pRxData ;
690 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
691 pRxData +=2U;
693 else
695 *pRxData++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
699 /* At end of TxRx process, restore husart->State to Ready */
700 husart->State = HAL_USART_STATE_READY;
702 /* Process Unlocked */
703 __HAL_UNLOCK(husart);
705 return HAL_OK;
707 else
709 return HAL_BUSY;
714 * @brief Send an amount of data in interrupt mode.
715 * @param husart USART handle.
716 * @param pTxData pointer to data buffer.
717 * @param Size amount of data to be sent.
718 * @retval HAL status
720 HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size)
722 if(husart->State == HAL_USART_STATE_READY)
724 if((pTxData == NULL) || (Size == 0U))
726 return HAL_ERROR;
729 /* Process Locked */
730 __HAL_LOCK(husart);
732 husart->pTxBuffPtr = pTxData;
733 husart->TxXferSize = Size;
734 husart->TxXferCount = Size;
736 husart->ErrorCode = HAL_USART_ERROR_NONE;
737 husart->State = HAL_USART_STATE_BUSY_TX;
739 /* The USART Error Interrupts: (Frame error, noise error, overrun error)
740 are not managed by the USART Transmit Process to avoid the overrun interrupt
741 when the usart mode is configured for transmit and receive "USART_MODE_TX_RX"
742 to benefit for the frame error and noise interrupts the usart mode should be
743 configured only for transmit "USART_MODE_TX" */
745 /* Process Unlocked */
746 __HAL_UNLOCK(husart);
748 /* Enable the USART Transmit Data Register Empty Interrupt */
749 __HAL_USART_ENABLE_IT(husart, USART_IT_TXE);
751 return HAL_OK;
753 else
755 return HAL_BUSY;
760 * @brief Receive an amount of data in interrupt mode.
761 * @note To receive synchronous data, dummy data are simultaneously transmitted.
762 * @param husart USART handle.
763 * @param pRxData pointer to data buffer.
764 * @param Size amount of data to be received.
765 * @retval HAL status
767 HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size)
769 if(husart->State == HAL_USART_STATE_READY)
771 if((pRxData == NULL) || (Size == 0U))
773 return HAL_ERROR;
776 /* Process Locked */
777 __HAL_LOCK(husart);
779 husart->pRxBuffPtr = pRxData;
780 husart->RxXferSize = Size;
781 husart->RxXferCount = Size;
783 USART_MASK_COMPUTATION(husart);
785 husart->ErrorCode = HAL_USART_ERROR_NONE;
786 husart->State = HAL_USART_STATE_BUSY_RX;
788 /* Process Unlocked */
789 __HAL_UNLOCK(husart);
791 /* Enable the USART Parity Error and Data Register not empty Interrupts */
792 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE);
794 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
795 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
797 /* Send dummy byte in order to generate the clock for the Slave to send the next data */
798 if(husart->Init.WordLength == USART_WORDLENGTH_9B)
800 husart->Instance->TDR = (USART_DUMMY_DATA & (uint16_t)0x01FFU);
802 else
804 husart->Instance->TDR = (USART_DUMMY_DATA & (uint16_t)0x00FFU);
807 return HAL_OK;
809 else
811 return HAL_BUSY;
816 * @brief Full-Duplex Send and Receive an amount of data in interrupt mode.
817 * @param husart USART handle.
818 * @param pTxData pointer to TX data buffer.
819 * @param pRxData pointer to RX data buffer.
820 * @param Size amount of data to be sent (same amount to be received).
821 * @retval HAL status
823 HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
826 if(husart->State == HAL_USART_STATE_READY)
828 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
830 return HAL_ERROR;
833 /* Process Locked */
834 __HAL_LOCK(husart);
836 husart->pRxBuffPtr = pRxData;
837 husart->RxXferSize = Size;
838 husart->RxXferCount = Size;
839 husart->pTxBuffPtr = pTxData;
840 husart->TxXferSize = Size;
841 husart->TxXferCount = Size;
843 /* Computation of USART mask to apply to RDR register */
844 USART_MASK_COMPUTATION(husart);
846 husart->ErrorCode = HAL_USART_ERROR_NONE;
847 husart->State = HAL_USART_STATE_BUSY_TX_RX;
849 /* Process Unlocked */
850 __HAL_UNLOCK(husart);
852 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
853 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
855 /* Enable the USART Parity Error and USART Data Register not empty Interrupts */
856 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE);
858 /* Enable the USART Transmit Data Register Empty Interrupt */
859 SET_BIT(husart->Instance->CR1, USART_CR1_TXEIE);
861 return HAL_OK;
863 else
865 return HAL_BUSY;
870 * @brief Send an amount of data in DMA mode.
871 * @param husart USART handle.
872 * @param pTxData pointer to data buffer.
873 * @param Size amount of data to be sent.
874 * @note This function starts a DMA transfer in interrupt mode meaning that
875 * DMA half transfer complete, DMA transfer complete and DMA transfer
876 * error interrupts are enabled
877 * @retval HAL status
879 HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size)
881 uint32_t *tmp=0U;
883 if(husart->State == HAL_USART_STATE_READY)
885 if((pTxData == NULL) || (Size == 0U))
887 return HAL_ERROR;
890 /* Process Locked */
891 __HAL_LOCK(husart);
893 husart->pTxBuffPtr = pTxData;
894 husart->TxXferSize = Size;
895 husart->TxXferCount = Size;
897 husart->ErrorCode = HAL_USART_ERROR_NONE;
898 husart->State = HAL_USART_STATE_BUSY_TX;
900 /* Set the USART DMA transfer complete callback */
901 husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt;
903 /* Set the USART DMA Half transfer complete callback */
904 husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt;
906 /* Set the DMA error callback */
907 husart->hdmatx->XferErrorCallback = USART_DMAError;
909 /* Enable the USART transmit DMA channel */
910 tmp = (uint32_t*)&pTxData;
911 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
913 /* Clear the TC flag in the ICR register */
914 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_TCF);
916 /* Process Unlocked */
917 __HAL_UNLOCK(husart);
919 /* Enable the DMA transfer for transmit request by setting the DMAT bit
920 in the USART CR3 register */
921 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
923 return HAL_OK;
925 else
927 return HAL_BUSY;
932 * @brief Receive an amount of data in DMA mode.
933 * @param husart USART handle.
934 * @param pRxData pointer to data buffer.
935 * @param Size amount of data to be received.
936 * @note When the USART parity is enabled (PCE = 1), the received data contain
937 * the parity bit (MSB position).
938 * @note The USART DMA transmit channel must be configured in order to generate the clock for the slave.
939 * @note This function starts a DMA transfer in interrupt mode meaning that
940 * DMA half transfer complete, DMA transfer complete and DMA transfer
941 * error interrupts are enabled
942 * @retval HAL status
944 HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size)
946 uint32_t *tmp;
948 /* Check that a Rx process is not already ongoing */
949 if(husart->State == HAL_USART_STATE_READY)
951 if((pRxData == NULL) || (Size == 0U))
953 return HAL_ERROR;
956 /* Process Locked */
957 __HAL_LOCK(husart);
959 husart->pRxBuffPtr = pRxData;
960 husart->RxXferSize = Size;
961 husart->pTxBuffPtr = pRxData;
962 husart->TxXferSize = Size;
964 husart->ErrorCode = HAL_USART_ERROR_NONE;
965 husart->State = HAL_USART_STATE_BUSY_RX;
967 /* Set the USART DMA Rx transfer complete callback */
968 husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt;
970 /* Set the USART DMA Half transfer complete callback */
971 husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt;
973 /* Set the USART DMA Rx transfer error callback */
974 husart->hdmarx->XferErrorCallback = USART_DMAError;
976 /* Enable the USART receive DMA channel */
977 tmp = (uint32_t*)&pRxData;
978 HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->RDR, *(uint32_t*)tmp, Size);
980 /* Enable the USART transmit DMA channel: the transmit channel is used in order
981 to generate in the non-blocking mode the clock to the slave device,
982 this mode isn't a simplex receive mode but a full-duplex receive mode */
983 /* Set the USART DMA Tx Complete and Error callback to Null */
984 husart->hdmatx->XferErrorCallback = NULL;
985 husart->hdmatx->XferHalfCpltCallback = NULL;
986 husart->hdmatx->XferCpltCallback = NULL;
987 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
989 /* Process Unlocked */
990 __HAL_UNLOCK(husart);
992 /* Enable the USART Parity Error Interrupt */
993 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
995 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
996 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
998 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
999 in the USART CR3 register */
1000 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1002 /* Enable the DMA transfer for transmit request by setting the DMAT bit
1003 in the USART CR3 register */
1004 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1006 return HAL_OK;
1008 else
1010 return HAL_BUSY;
1015 * @brief Full-Duplex Transmit Receive an amount of data in non-blocking mode.
1016 * @param husart USART handle.
1017 * @param pTxData pointer to TX data buffer.
1018 * @param pRxData pointer to RX data buffer.
1019 * @param Size amount of data to be received/sent.
1020 * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit.
1021 * @note This function starts a 2 DMA transfers in interrupt mode meaning that
1022 * DMA half transfer complete, DMA transfer complete and DMA transfer
1023 * error interrupts are enabled
1024 * @retval HAL status
1026 HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
1028 uint32_t *tmp;
1030 if(husart->State == HAL_USART_STATE_READY)
1032 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
1034 return HAL_ERROR;
1037 /* Process Locked */
1038 __HAL_LOCK(husart);
1040 husart->pRxBuffPtr = pRxData;
1041 husart->RxXferSize = Size;
1042 husart->pTxBuffPtr = pTxData;
1043 husart->TxXferSize = Size;
1045 husart->ErrorCode = HAL_USART_ERROR_NONE;
1046 husart->State = HAL_USART_STATE_BUSY_TX_RX;
1048 /* Set the USART DMA Rx transfer complete callback */
1049 husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt;
1051 /* Set the USART DMA Half transfer complete callback */
1052 husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt;
1054 /* Set the USART DMA Tx transfer complete callback */
1055 husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt;
1057 /* Set the USART DMA Half transfer complete callback */
1058 husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt;
1060 /* Set the USART DMA Tx transfer error callback */
1061 husart->hdmatx->XferErrorCallback = USART_DMAError;
1063 /* Set the USART DMA Rx transfer error callback */
1064 husart->hdmarx->XferErrorCallback = USART_DMAError;
1066 /* Enable the USART receive DMA channel */
1067 tmp = (uint32_t*)&pRxData;
1068 HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->RDR, *(uint32_t*)tmp, Size);
1070 /* Enable the USART transmit DMA channel */
1071 tmp = (uint32_t*)&pTxData;
1072 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
1074 /* Process Unlocked */
1075 __HAL_UNLOCK(husart);
1077 /* Enable the USART Parity Error Interrupt */
1078 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1080 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1081 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
1083 /* Clear the TC flag in the ICR register */
1084 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_TCF);
1086 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
1087 in the USART CR3 register */
1088 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1090 /* Enable the DMA transfer for transmit request by setting the DMAT bit
1091 in the USART CR3 register */
1092 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1094 return HAL_OK;
1096 else
1098 return HAL_BUSY;
1103 * @brief Pause the DMA Transfer.
1104 * @param husart USART handle.
1105 * @retval HAL status
1107 HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart)
1109 /* Process Locked */
1110 __HAL_LOCK(husart);
1112 if( (husart->State == HAL_USART_STATE_BUSY_TX) &&
1113 (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)))
1115 /* Disable the USART DMA Tx request */
1116 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1118 else if( (husart->State == HAL_USART_STATE_BUSY_RX) ||
1119 (husart->State == HAL_USART_STATE_BUSY_TX_RX) )
1121 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT))
1123 /* Disable the USART DMA Tx request */
1124 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1126 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR))
1128 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
1129 CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1130 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1132 /* Disable the USART DMA Rx request */
1133 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1137 /* Process Unlocked */
1138 __HAL_UNLOCK(husart);
1140 return HAL_OK;
1144 * @brief Resume the DMA Transfer.
1145 * @param husart USART handle.
1146 * @retval HAL status
1148 HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart)
1150 /* Process Locked */
1151 __HAL_LOCK(husart);
1153 if(husart->State == HAL_USART_STATE_BUSY_TX)
1155 /* Enable the USART DMA Tx request */
1156 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1158 else if( (husart->State == HAL_USART_STATE_BUSY_RX) ||
1159 (husart->State == HAL_USART_STATE_BUSY_TX_RX) )
1161 /* Clear the Overrun flag before resuming the Rx transfer*/
1162 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_OREF);
1164 /* Reenable PE and ERR (Frame error, noise error, overrun error) interrupts */
1165 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1166 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
1168 /* Enable the USART DMA Rx request before the DMA Tx request */
1169 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1171 /* Enable the USART DMA Tx request */
1172 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1175 /* Process Unlocked */
1176 __HAL_UNLOCK(husart);
1178 return HAL_OK;
1182 * @brief Stop the DMA Transfer.
1183 * @param husart USART handle.
1184 * @retval HAL status
1186 HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart)
1188 /* The Lock is not implemented on this API to allow the user application
1189 to call the HAL USART API under callbacks HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback() /
1190 HAL_USART_TxHalfCpltCallback() / HAL_USART_RxHalfCpltCallback ():
1191 indeed, when HAL_DMA_Abort() API is called, the DMA TX/RX Transfer or Half Transfer complete interrupt is
1192 generated if the DMA transfer interruption occurs at the middle or at the end of the stream
1193 and the corresponding call back is executed.
1196 /* Disable the USART Tx/Rx DMA requests */
1197 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1198 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1200 /* Abort the USART DMA tx channel */
1201 if(husart->hdmatx != NULL)
1203 HAL_DMA_Abort(husart->hdmatx);
1205 /* Abort the USART DMA rx channel */
1206 if(husart->hdmarx != NULL)
1208 HAL_DMA_Abort(husart->hdmarx);
1211 USART_EndTransfer(husart);
1212 husart->State = HAL_USART_STATE_READY;
1214 return HAL_OK;
1218 * @brief Abort ongoing transfers (blocking mode).
1219 * @param husart USART handle.
1220 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1221 * This procedure performs following operations :
1222 * - Disable USART Interrupts (Tx and Rx)
1223 * - Disable the DMA transfer in the peripheral register (if enabled)
1224 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1225 * - Set handle State to READY
1226 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1227 * @retval HAL status
1229 HAL_StatusTypeDef HAL_USART_Abort(USART_HandleTypeDef *husart)
1231 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1232 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE));
1233 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1235 /* Disable the USART DMA Tx request if enabled */
1236 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT))
1238 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1240 /* Abort the USART DMA Tx channel : use blocking DMA Abort API (no callback) */
1241 if(husart->hdmatx != NULL)
1243 /* Set the USART DMA Abort callback to Null.
1244 No call back execution at end of DMA abort procedure */
1245 husart->hdmatx->XferAbortCallback = NULL;
1247 HAL_DMA_Abort(husart->hdmatx);
1251 /* Disable the USART DMA Rx request if enabled */
1252 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR))
1254 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1256 /* Abort the USART DMA Rx channel : use blocking DMA Abort API (no callback) */
1257 if(husart->hdmarx != NULL)
1259 /* Set the USART DMA Abort callback to Null.
1260 No call back execution at end of DMA abort procedure */
1261 husart->hdmarx->XferAbortCallback = NULL;
1263 HAL_DMA_Abort(husart->hdmarx);
1267 /* Reset Tx and Rx transfer counters */
1268 husart->TxXferCount = 0U;
1269 husart->RxXferCount = 0U;
1271 /* Clear the Error flags in the ICR register */
1272 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_OREF | USART_CLEAR_NEF | USART_CLEAR_PEF | USART_CLEAR_FEF);
1274 /* Restore husart->State to Ready */
1275 husart->State = HAL_USART_STATE_READY;
1277 /* Reset Handle ErrorCode to No Error */
1278 husart->ErrorCode = HAL_USART_ERROR_NONE;
1280 return HAL_OK;
1284 * @brief Abort ongoing transfers (Interrupt mode).
1285 * @param husart USART handle.
1286 * @note This procedure could be used for aborting any ongoing transfer started in Interrupt or DMA mode.
1287 * This procedure performs following operations :
1288 * - Disable USART Interrupts (Tx and Rx)
1289 * - Disable the DMA transfer in the peripheral register (if enabled)
1290 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1291 * - Set handle State to READY
1292 * - At abort completion, call user abort complete callback
1293 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1294 * considered as completed only when user abort complete callback is executed (not when exiting function).
1295 * @retval HAL status
1297 HAL_StatusTypeDef HAL_USART_Abort_IT(USART_HandleTypeDef *husart)
1299 uint32_t abortcplt = 1U;
1301 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1302 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE));
1303 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1305 /* If DMA Tx and/or DMA Rx Handles are associated to USART Handle, DMA Abort complete callbacks should be initialised
1306 before any call to DMA Abort functions */
1307 /* DMA Tx Handle is valid */
1308 if(husart->hdmatx != NULL)
1310 /* Set DMA Abort Complete callback if USART DMA Tx request if enabled.
1311 Otherwise, set it to NULL */
1312 if(HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT))
1314 husart->hdmatx->XferAbortCallback = USART_DMATxAbortCallback;
1316 else
1318 husart->hdmatx->XferAbortCallback = NULL;
1321 /* DMA Rx Handle is valid */
1322 if(husart->hdmarx != NULL)
1324 /* Set DMA Abort Complete callback if USART DMA Rx request if enabled.
1325 Otherwise, set it to NULL */
1326 if(HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR))
1328 husart->hdmarx->XferAbortCallback = USART_DMARxAbortCallback;
1330 else
1332 husart->hdmarx->XferAbortCallback = NULL;
1336 /* Disable the USART DMA Tx request if enabled */
1337 if(HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT))
1339 /* Disable DMA Tx at USART level */
1340 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1342 /* Abort the USART DMA Tx channel : use non blocking DMA Abort API (callback) */
1343 if(husart->hdmatx != NULL)
1345 /* USART Tx DMA Abort callback has already been initialised :
1346 will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */
1348 /* Abort DMA TX */
1349 if(HAL_DMA_Abort_IT(husart->hdmatx) != HAL_OK)
1351 husart->hdmatx->XferAbortCallback = NULL;
1353 else
1355 abortcplt = 0U;
1360 /* Disable the USART DMA Rx request if enabled */
1361 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR))
1363 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1365 /* Abort the USART DMA Rx channel : use non blocking DMA Abort API (callback) */
1366 if(husart->hdmarx != NULL)
1368 /* USART Rx DMA Abort callback has already been initialised :
1369 will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */
1371 /* Abort DMA RX */
1372 if(HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK)
1374 husart->hdmarx->XferAbortCallback = NULL;
1375 abortcplt = 1U;
1377 else
1379 abortcplt = 0U;
1384 /* if no DMA abort complete callback execution is required => call user Abort Complete callback */
1385 if (abortcplt == 1U)
1387 /* Reset Tx and Rx transfer counters */
1388 husart->TxXferCount = 0U;
1389 husart->RxXferCount = 0U;
1391 /* Reset errorCode */
1392 husart->ErrorCode = HAL_USART_ERROR_NONE;
1394 /* Clear the Error flags in the ICR register */
1395 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_OREF | USART_CLEAR_NEF | USART_CLEAR_PEF | USART_CLEAR_FEF);
1397 /* Restore husart->State to Ready */
1398 husart->State = HAL_USART_STATE_READY;
1400 /* As no DMA to be aborted, call directly user Abort complete callback */
1401 HAL_USART_AbortCpltCallback(husart);
1404 return HAL_OK;
1408 * @brief Handle USART interrupt request.
1409 * @param husart USART handle.
1410 * @retval None
1412 void HAL_USART_IRQHandler(USART_HandleTypeDef *husart)
1414 uint32_t isrflags = READ_REG(husart->Instance->ISR);
1415 uint32_t cr1its = READ_REG(husart->Instance->CR1);
1416 uint32_t cr3its;
1417 uint32_t errorflags;
1419 /* If no error occurs */
1420 errorflags = (isrflags & (uint32_t)(USART_ISR_PE | USART_ISR_FE | USART_ISR_ORE | USART_ISR_NE));
1421 if (errorflags == RESET)
1423 /* USART in mode Receiver ---------------------------------------------------*/
1424 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1426 if(husart->State == HAL_USART_STATE_BUSY_RX)
1428 USART_Receive_IT(husart);
1430 else
1432 USART_TransmitReceive_IT(husart);
1434 return;
1438 /* If some errors occur */
1439 cr3its = READ_REG(husart->Instance->CR3);
1440 if( (errorflags != RESET)
1441 && ( ((cr3its & USART_CR3_EIE) != RESET)
1442 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET)) )
1444 /* USART parity error interrupt occurred -------------------------------------*/
1445 if(((isrflags & USART_ISR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET))
1447 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_PEF);
1449 husart->ErrorCode |= HAL_USART_ERROR_PE;
1452 /* USART frame error interrupt occurred --------------------------------------*/
1453 if(((isrflags & USART_ISR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1455 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_FEF);
1457 husart->ErrorCode |= HAL_USART_ERROR_FE;
1460 /* USART noise error interrupt occurred --------------------------------------*/
1461 if(((isrflags & USART_ISR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1463 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_NEF);
1465 husart->ErrorCode |= HAL_USART_ERROR_NE;
1468 /* USART Over-Run interrupt occurred -----------------------------------------*/
1469 if(((isrflags & USART_ISR_ORE) != RESET) &&
1470 (((cr1its & USART_CR1_RXNEIE) != RESET) || ((cr3its & USART_CR3_EIE) != RESET)))
1472 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_OREF);
1474 husart->ErrorCode |= HAL_USART_ERROR_ORE;
1477 /* Call USART Error Call back function if need be --------------------------*/
1478 if(husart->ErrorCode != HAL_USART_ERROR_NONE)
1480 /* USART in mode Receiver ---------------------------------------------------*/
1481 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1483 if(husart->State == HAL_USART_STATE_BUSY_RX)
1485 USART_Receive_IT(husart);
1487 else
1489 USART_TransmitReceive_IT(husart);
1493 /* If Overrun error occurs, or if any error occurs in DMA mode reception,
1494 consider error as blocking */
1495 if (((husart->ErrorCode & HAL_USART_ERROR_ORE) != RESET) ||
1496 (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)))
1498 /* Blocking error : transfer is aborted
1499 Set the USART state ready to be able to start again the process,
1500 Disable Interrupts, and disable DMA requests, if ongoing */
1501 USART_EndTransfer(husart);
1503 /* Disable the USART DMA Rx request if enabled */
1504 if (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR))
1506 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR | USART_CR3_DMAR);
1508 /* Abort the USART DMA Tx channel */
1509 if(husart->hdmatx != NULL)
1511 /* Set the USART Tx DMA Abort callback to NULL : no callback
1512 executed at end of DMA abort procedure */
1513 husart->hdmatx->XferAbortCallback = NULL;
1515 /* Abort DMA TX */
1516 HAL_DMA_Abort_IT(husart->hdmatx);
1519 /* Abort the USART DMA Rx channel */
1520 if(husart->hdmarx != NULL)
1522 /* Set the USART Rx DMA Abort callback :
1523 will lead to call HAL_USART_ErrorCallback() at end of DMA abort procedure */
1524 husart->hdmarx->XferAbortCallback = USART_DMAAbortOnError;
1526 /* Abort DMA RX */
1527 if(HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK)
1529 /* Call Directly husart->hdmarx->XferAbortCallback function in case of error */
1530 husart->hdmarx->XferAbortCallback(husart->hdmarx);
1533 else
1535 /* Call user error callback */
1536 HAL_USART_ErrorCallback(husart);
1539 else
1541 /* Call user error callback */
1542 HAL_USART_ErrorCallback(husart);
1545 else
1547 /* Non Blocking error : transfer could go on.
1548 Error is notified to user through user error callback */
1549 HAL_USART_ErrorCallback(husart);
1550 husart->ErrorCode = HAL_USART_ERROR_NONE;
1553 return;
1555 } /* End if some error occurs */
1558 /* USART in mode Transmitter ------------------------------------------------*/
1559 if(((isrflags & USART_ISR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET))
1561 if(husart->State == HAL_USART_STATE_BUSY_TX)
1563 USART_Transmit_IT(husart);
1565 else
1567 USART_TransmitReceive_IT(husart);
1569 return;
1572 /* USART in mode Transmitter (transmission end) -----------------------------*/
1573 if(((isrflags & USART_ISR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET))
1575 USART_EndTransmit_IT(husart);
1576 return;
1582 * @brief Tx Transfer completed callback.
1583 * @param husart USART handle.
1584 * @retval None
1586 __weak void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart)
1588 /* Prevent unused argument(s) compilation warning */
1589 UNUSED(husart);
1591 /* NOTE : This function should not be modified, when the callback is needed,
1592 the HAL_USART_TxCpltCallback can be implemented in the user file.
1597 * @brief Tx Half Transfer completed callback.
1598 * @param husart USART handle.
1599 * @retval None
1601 __weak void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart)
1603 /* Prevent unused argument(s) compilation warning */
1604 UNUSED(husart);
1606 /* NOTE: This function should not be modified, when the callback is needed,
1607 the HAL_USART_TxHalfCpltCallback can be implemented in the user file.
1612 * @brief Rx Transfer completed callback.
1613 * @param husart USART handle.
1614 * @retval None
1616 __weak void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart)
1618 /* Prevent unused argument(s) compilation warning */
1619 UNUSED(husart);
1621 /* NOTE: This function should not be modified, when the callback is needed,
1622 the HAL_USART_RxCpltCallback can be implemented in the user file.
1627 * @brief Rx Half Transfer completed callback.
1628 * @param husart USART handle.
1629 * @retval None
1631 __weak void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart)
1633 /* Prevent unused argument(s) compilation warning */
1634 UNUSED(husart);
1636 /* NOTE : This function should not be modified, when the callback is needed,
1637 the HAL_USART_RxHalfCpltCallback can be implemented in the user file
1642 * @brief Tx/Rx Transfers completed callback for the non-blocking process.
1643 * @param husart USART handle.
1644 * @retval None
1646 __weak void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart)
1648 /* Prevent unused argument(s) compilation warning */
1649 UNUSED(husart);
1651 /* NOTE : This function should not be modified, when the callback is needed,
1652 the HAL_USART_TxRxCpltCallback can be implemented in the user file
1657 * @brief USART error callback.
1658 * @param husart USART handle.
1659 * @retval None
1661 __weak void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart)
1663 /* Prevent unused argument(s) compilation warning */
1664 UNUSED(husart);
1666 /* NOTE : This function should not be modified, when the callback is needed,
1667 the HAL_USART_ErrorCallback can be implemented in the user file.
1672 * @brief USART Abort Complete callback.
1673 * @param husart USART handle.
1674 * @retval None
1676 __weak void HAL_USART_AbortCpltCallback (USART_HandleTypeDef *husart)
1678 /* Prevent unused argument(s) compilation warning */
1679 UNUSED(husart);
1681 /* NOTE : This function should not be modified, when the callback is needed,
1682 the HAL_USART_AbortCpltCallback can be implemented in the user file.
1687 * @}
1690 /** @defgroup USART_Exported_Functions_Group3 Peripheral State and Error functions
1691 * @brief USART Peripheral State and Error functions
1693 @verbatim
1694 ==============================================================================
1695 ##### Peripheral State and Error functions #####
1696 ==============================================================================
1697 [..]
1698 This subsection provides functions allowing to :
1699 (+) Return the USART handle state
1700 (+) Return the USART handle error code
1702 @endverbatim
1703 * @{
1708 * @brief Return the USART handle state.
1709 * @param husart pointer to a USART_HandleTypeDef structure that contains
1710 * the configuration information for the specified USART.
1711 * @retval USART handle state
1713 HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart)
1715 return husart->State;
1719 * @brief Return the USART error code.
1720 * @param husart pointer to a USART_HandleTypeDef structure that contains
1721 * the configuration information for the specified USART.
1722 * @retval USART handle Error Code
1724 uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart)
1726 return husart->ErrorCode;
1730 * @}
1734 * @}
1737 /** @defgroup USART_Private_Functions USART Private Functions
1738 * @brief USART Private functions
1740 @verbatim
1741 [..]
1742 This subsection provides a set of functions allowing to control the USART.
1743 (+) USART_SetConfig() API is used to set the USART communication parameters.
1744 (+) USART_CheckIdleState() APi ensures that TEACK and/or REACK bits are set after initialization
1746 @endverbatim
1747 * @{
1750 * @brief End ongoing transfer on USART peripheral (following error detection or Transfer completion).
1751 * @param husart USART handle.
1752 * @retval None
1754 static void USART_EndTransfer(USART_HandleTypeDef *husart)
1756 /* Disable TXEIE and TCIE interrupts */
1757 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1758 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | USART_CR1_PEIE));
1759 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1761 /* At end of process, restore husart->State to Ready */
1762 husart->State = HAL_USART_STATE_READY;
1766 * @brief DMA USART transmit process complete callback.
1767 * @param hdma DMA handle.
1768 * @retval None
1770 static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma)
1772 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1774 /* DMA Normal mode */
1775 if ( HAL_IS_BIT_CLR(hdma->Instance->CCR, DMA_CCR_CIRC) )
1777 husart->TxXferCount = 0U;
1779 if(husart->State == HAL_USART_STATE_BUSY_TX)
1781 /* Disable the DMA transfer for transmit request by resetting the DMAT bit
1782 in the USART CR3 register */
1783 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1785 /* Enable the USART Transmit Complete Interrupt */
1786 __HAL_USART_ENABLE_IT(husart, USART_IT_TC);
1789 /* DMA Circular mode */
1790 else
1792 if(husart->State == HAL_USART_STATE_BUSY_TX)
1794 HAL_USART_TxCpltCallback(husart);
1800 * @brief DMA USART transmit process half complete callback.
1801 * @param hdma DMA handle.
1802 * @retval None
1804 static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma)
1806 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1808 HAL_USART_TxHalfCpltCallback(husart);
1812 * @brief DMA USART receive process complete callback.
1813 * @param hdma DMA handle.
1814 * @retval None
1816 static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
1818 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1820 /* DMA Normal mode */
1821 if ( HAL_IS_BIT_CLR(hdma->Instance->CCR, DMA_CCR_CIRC) )
1823 husart->RxXferCount = 0U;
1825 /* Disable PE and ERR (Frame error, noise error, overrun error) interrupts */
1826 CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1827 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1829 /* Disable the DMA RX transfer for the receiver request by resetting the DMAR bit
1830 in USART CR3 register */
1831 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1832 /* similarly, disable the DMA TX transfer that was started to provide the
1833 clock to the slave device */
1834 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1836 if(husart->State == HAL_USART_STATE_BUSY_RX)
1838 HAL_USART_RxCpltCallback(husart);
1840 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1841 else
1843 HAL_USART_TxRxCpltCallback(husart);
1845 husart->State= HAL_USART_STATE_READY;
1847 /* DMA circular mode */
1848 else
1850 if(husart->State == HAL_USART_STATE_BUSY_RX)
1852 HAL_USART_RxCpltCallback(husart);
1854 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1855 else
1857 HAL_USART_TxRxCpltCallback(husart);
1864 * @brief DMA USART receive process half complete callback.
1865 * @param hdma DMA handle.
1866 * @retval None
1868 static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma)
1870 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1872 HAL_USART_RxHalfCpltCallback(husart);
1876 * @brief DMA USART communication error callback.
1877 * @param hdma DMA handle.
1878 * @retval None
1880 static void USART_DMAError(DMA_HandleTypeDef *hdma)
1882 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1884 husart->RxXferCount = 0U;
1885 husart->TxXferCount = 0U;
1886 USART_EndTransfer(husart);
1888 husart->ErrorCode |= HAL_USART_ERROR_DMA;
1889 husart->State= HAL_USART_STATE_READY;
1891 HAL_USART_ErrorCallback(husart);
1895 * @brief DMA USART communication abort callback, when initiated by HAL services on Error
1896 * (To be called at end of DMA Abort procedure following error occurrence).
1897 * @param hdma DMA handle.
1898 * @retval None
1900 static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma)
1902 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)(hdma->Parent);
1903 husart->RxXferCount = 0U;
1904 husart->TxXferCount = 0U;
1906 HAL_USART_ErrorCallback(husart);
1910 * @brief DMA USART Tx communication abort callback, when initiated by user
1911 * (To be called at end of DMA Tx Abort procedure following user abort request).
1912 * @note When this callback is executed, User Abort complete call back is called only if no
1913 * Abort still ongoing for Rx DMA Handle.
1914 * @param hdma DMA handle.
1915 * @retval None
1917 static void USART_DMATxAbortCallback(DMA_HandleTypeDef *hdma)
1919 USART_HandleTypeDef* husart = (USART_HandleTypeDef* )(hdma->Parent);
1921 husart->hdmatx->XferAbortCallback = NULL;
1923 /* Check if an Abort process is still ongoing */
1924 if(husart->hdmarx != NULL)
1926 if(husart->hdmarx->XferAbortCallback != NULL)
1928 return;
1932 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1933 husart->TxXferCount = 0U;
1934 husart->RxXferCount = 0U;
1936 /* Reset errorCode */
1937 husart->ErrorCode = HAL_USART_ERROR_NONE;
1939 /* Clear the Error flags in the ICR register */
1940 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_OREF | USART_CLEAR_NEF | USART_CLEAR_PEF | USART_CLEAR_FEF);
1942 /* Restore husart->State to Ready */
1943 husart->State = HAL_USART_STATE_READY;
1945 /* Call user Abort complete callback */
1946 HAL_USART_AbortCpltCallback(husart);
1951 * @brief DMA USART Rx communication abort callback, when initiated by user
1952 * (To be called at end of DMA Rx Abort procedure following user abort request).
1953 * @note When this callback is executed, User Abort complete call back is called only if no
1954 * Abort still ongoing for Tx DMA Handle.
1955 * @param hdma DMA handle.
1956 * @retval None
1958 static void USART_DMARxAbortCallback(DMA_HandleTypeDef *hdma)
1960 USART_HandleTypeDef* husart = (USART_HandleTypeDef* )(hdma->Parent);
1962 husart->hdmarx->XferAbortCallback = NULL;
1964 /* Check if an Abort process is still ongoing */
1965 if(husart->hdmatx != NULL)
1967 if(husart->hdmatx->XferAbortCallback != NULL)
1969 return;
1973 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1974 husart->TxXferCount = 0U;
1975 husart->RxXferCount = 0U;
1977 /* Reset errorCode */
1978 husart->ErrorCode = HAL_USART_ERROR_NONE;
1980 /* Clear the Error flags in the ICR register */
1981 __HAL_USART_CLEAR_FLAG(husart, USART_CLEAR_OREF | USART_CLEAR_NEF | USART_CLEAR_PEF | USART_CLEAR_FEF);
1983 /* Restore husart->State to Ready */
1984 husart->State = HAL_USART_STATE_READY;
1986 /* Call user Abort complete callback */
1987 HAL_USART_AbortCpltCallback(husart);
1992 * @brief Handle USART Communication Timeout.
1993 * @param husart USART handle.
1994 * @param Flag Specifies the USART flag to check.
1995 * @param Status the Flag status (SET or RESET).
1996 * @param Tickstart Tick start value
1997 * @param Timeout timeout duration.
1998 * @retval HAL status
2000 static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout)
2002 /* Wait until flag is set */
2003 while((__HAL_USART_GET_FLAG(husart, Flag) ? SET : RESET) == Status)
2005 /* Check for the Timeout */
2006 if(Timeout != HAL_MAX_DELAY)
2008 if((Timeout == 0U) || ((HAL_GetTick()-Tickstart) > Timeout))
2010 /* Disable TXE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts for the interrupt process */
2011 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE | USART_CR1_TXEIE));
2012 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
2014 husart->State= HAL_USART_STATE_READY;
2016 /* Process Unlocked */
2017 __HAL_UNLOCK(husart);
2019 return HAL_TIMEOUT;
2023 return HAL_OK;
2028 * @brief Configure the USART peripheral.
2029 * @param husart USART handle.
2030 * @retval HAL status
2032 static HAL_StatusTypeDef USART_SetConfig(USART_HandleTypeDef *husart)
2034 uint32_t tmpreg = 0x0U;
2035 USART_ClockSourceTypeDef clocksource = USART_CLOCKSOURCE_UNDEFINED;
2036 HAL_StatusTypeDef ret = HAL_OK;
2037 uint16_t brrtemp = 0x0000U;
2038 uint16_t usartdiv = 0x0000U;
2040 /* Check the parameters */
2041 assert_param(IS_USART_POLARITY(husart->Init.CLKPolarity));
2042 assert_param(IS_USART_PHASE(husart->Init.CLKPhase));
2043 assert_param(IS_USART_LASTBIT(husart->Init.CLKLastBit));
2044 assert_param(IS_USART_BAUDRATE(husart->Init.BaudRate));
2045 assert_param(IS_USART_WORD_LENGTH(husart->Init.WordLength));
2046 assert_param(IS_USART_STOPBITS(husart->Init.StopBits));
2047 assert_param(IS_USART_PARITY(husart->Init.Parity));
2048 assert_param(IS_USART_MODE(husart->Init.Mode));
2051 /*-------------------------- USART CR1 Configuration -----------------------*/
2052 /* Clear M, PCE, PS, TE and RE bits and configure
2053 * the USART Word Length, Parity and Mode:
2054 * set the M bits according to husart->Init.WordLength value
2055 * set PCE and PS bits according to husart->Init.Parity value
2056 * set TE and RE bits according to husart->Init.Mode value
2057 * force OVER8 to 1 to allow to reach the maximum speed (Fclock/8) */
2058 tmpreg = (uint32_t)husart->Init.WordLength | husart->Init.Parity | husart->Init.Mode | USART_CR1_OVER8;
2059 MODIFY_REG(husart->Instance->CR1, USART_CR1_FIELDS, tmpreg);
2061 /*---------------------------- USART CR2 Configuration ---------------------*/
2062 /* Clear and configure the USART Clock, CPOL, CPHA, LBCL and STOP bits:
2063 * set CPOL bit according to husart->Init.CLKPolarity value
2064 * set CPHA bit according to husart->Init.CLKPhase value
2065 * set LBCL bit according to husart->Init.CLKLastBit value
2066 * set STOP[13:12] bits according to husart->Init.StopBits value */
2067 tmpreg = (uint32_t)(USART_CLOCK_ENABLE);
2068 tmpreg |= ((uint32_t)husart->Init.CLKPolarity | (uint32_t)husart->Init.CLKPhase);
2069 tmpreg |= ((uint32_t)husart->Init.CLKLastBit | (uint32_t)husart->Init.StopBits);
2070 MODIFY_REG(husart->Instance->CR2, USART_CR2_FIELDS, tmpreg);
2072 /*-------------------------- USART CR3 Configuration -----------------------*/
2073 /* no CR3 register configuration */
2075 /*-------------------------- USART BRR Configuration -----------------------*/
2076 /* BRR is filled-up according to OVER8 bit setting which is forced to 1 */
2077 USART_GETCLOCKSOURCE(husart, clocksource);
2078 switch (clocksource)
2080 case USART_CLOCKSOURCE_PCLK1:
2081 usartdiv = (uint16_t)(((2U*HAL_RCC_GetPCLK1Freq()) + (husart->Init.BaudRate/2U)) / husart->Init.BaudRate);
2082 break;
2083 case USART_CLOCKSOURCE_PCLK2:
2084 usartdiv = (uint16_t)(((2U*HAL_RCC_GetPCLK2Freq()) + (husart->Init.BaudRate/2U)) / husart->Init.BaudRate);
2085 break;
2086 case USART_CLOCKSOURCE_HSI:
2087 usartdiv = (uint16_t)(((2U*HSI_VALUE) + (husart->Init.BaudRate/2U)) / husart->Init.BaudRate);
2088 break;
2089 case USART_CLOCKSOURCE_SYSCLK:
2090 usartdiv = (uint16_t)(((2U*HAL_RCC_GetSysClockFreq()) + (husart->Init.BaudRate/2U)) / husart->Init.BaudRate);
2091 break;
2092 case USART_CLOCKSOURCE_LSE:
2093 usartdiv = (uint16_t)(((2U*LSE_VALUE) + (husart->Init.BaudRate/2U)) / husart->Init.BaudRate);
2094 break;
2095 case USART_CLOCKSOURCE_UNDEFINED:
2096 default:
2097 ret = HAL_ERROR;
2098 break;
2101 brrtemp = usartdiv & 0xFFF0U;
2102 brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U);
2103 husart->Instance->BRR = brrtemp;
2105 return ret;
2109 * @brief Check the USART Idle State.
2110 * @param husart USART handle.
2111 * @retval HAL status
2113 static HAL_StatusTypeDef USART_CheckIdleState(USART_HandleTypeDef *husart)
2115 uint32_t tickstart = 0U;
2117 /* Initialize the USART ErrorCode */
2118 husart->ErrorCode = HAL_USART_ERROR_NONE;
2120 /* Init tickstart for timeout managment*/
2121 tickstart = HAL_GetTick();
2123 /* Check if the Transmitter is enabled */
2124 if((husart->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE)
2126 /* Wait until TEACK flag is set */
2127 if(USART_WaitOnFlagUntilTimeout(husart, USART_ISR_TEACK, RESET, tickstart, USART_TEACK_REACK_TIMEOUT) != HAL_OK)
2129 /* Timeout Occured */
2130 return HAL_TIMEOUT;
2134 /* REACK bit in ISR is checked only when available (not to be checked on all instances).
2135 Bit is defined only for USART instances supporting WakeUp from Stop Mode feature.
2137 if (IS_UART_WAKEUP_FROMSTOP_INSTANCE(husart->Instance))
2139 /* Check if the Receiver is enabled */
2140 if((husart->Instance->CR1 & USART_CR1_RE) == USART_CR1_RE)
2142 /* Wait until REACK flag is set */
2143 if(USART_WaitOnFlagUntilTimeout(husart, USART_ISR_REACK, RESET, tickstart, USART_TEACK_REACK_TIMEOUT) != HAL_OK)
2145 /* Timeout occurred */
2146 return HAL_TIMEOUT;
2151 /* Initialize the USART state*/
2152 husart->State= HAL_USART_STATE_READY;
2154 /* Process Unlocked */
2155 __HAL_UNLOCK(husart);
2157 return HAL_OK;
2162 * @brief Simplex send an amount of data in non-blocking mode.
2163 * @note Function called under interruption only, once
2164 * interruptions have been enabled by HAL_USART_Transmit_IT().
2165 * @note The USART errors are not managed to avoid the overrun error.
2166 * @param husart USART handle.
2167 * @retval HAL status
2169 static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart)
2171 uint16_t* tmp=0U;
2173 /* Check that a Tx process is ongoing */
2174 if(husart->State == HAL_USART_STATE_BUSY_TX)
2177 if(husart->TxXferCount == 0U)
2179 /* Disable the USART Transmit data register empty interrupt */
2180 __HAL_USART_DISABLE_IT(husart, USART_IT_TXE);
2182 /* Enable the USART Transmit Complete Interrupt */
2183 __HAL_USART_ENABLE_IT(husart, USART_IT_TC);
2185 return HAL_OK;
2187 else
2189 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
2191 tmp = (uint16_t*) husart->pTxBuffPtr;
2192 husart->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
2193 husart->pTxBuffPtr += 2U;
2195 else
2197 husart->Instance->TDR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0xFFU);
2200 husart->TxXferCount--;
2202 return HAL_OK;
2205 else
2207 return HAL_BUSY;
2213 * @brief Wraps up transmission in non-blocking mode.
2214 * @param husart Pointer to a USART_HandleTypeDef structure that contains
2215 * the configuration information for the specified USART module.
2216 * @retval HAL status
2218 static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart)
2220 /* Disable the USART Transmit Complete Interrupt */
2221 __HAL_USART_DISABLE_IT(husart, USART_IT_TC);
2223 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2224 __HAL_USART_DISABLE_IT(husart, USART_IT_ERR);
2226 /* Tx process is ended, restore husart->State to Ready */
2227 husart->State = HAL_USART_STATE_READY;
2229 HAL_USART_TxCpltCallback(husart);
2231 return HAL_OK;
2236 * @brief Simplex receive an amount of data in non-blocking mode.
2237 * @note Function called under interruption only, once
2238 * interruptions have been enabled by HAL_USART_Receive_IT().
2239 * @param husart USART handle
2240 * @retval HAL status
2242 static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart)
2244 uint16_t* tmp=0U;
2245 uint16_t uhMask = husart->Mask;
2247 if(husart->State == HAL_USART_STATE_BUSY_RX)
2250 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
2252 tmp = (uint16_t*) husart->pRxBuffPtr;
2253 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
2254 husart->pRxBuffPtr += 2U;
2256 else
2258 *husart->pRxBuffPtr++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
2261 /* Send dummy byte in order to generate the clock for the Slave to Send the next data */
2262 husart->Instance->TDR = (USART_DUMMY_DATA & (uint16_t)0x00FFU);
2264 if(--husart->RxXferCount == 0U)
2266 /* Disable the USART Parity Error Interrupt and RXNE interrupt*/
2267 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
2269 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2270 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
2272 /* Rx process is completed, restore husart->State to Ready */
2273 husart->State = HAL_USART_STATE_READY;
2275 HAL_USART_RxCpltCallback(husart);
2277 return HAL_OK;
2280 return HAL_OK;
2282 else
2284 return HAL_BUSY;
2289 * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking).
2290 * @note Function called under interruption only, once
2291 * interruptions have been enabled by HAL_USART_TransmitReceive_IT().
2292 * @param husart USART handle.
2293 * @retval HAL status
2295 static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart)
2297 uint16_t* tmp=0U;
2298 uint16_t uhMask = husart->Mask;
2300 if(husart->State == HAL_USART_STATE_BUSY_TX_RX)
2303 if(husart->TxXferCount != 0x00U)
2305 if(__HAL_USART_GET_FLAG(husart, USART_FLAG_TXE) != RESET)
2307 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
2309 tmp = (uint16_t*) husart->pTxBuffPtr;
2310 husart->Instance->TDR = (uint16_t)(*tmp & uhMask);
2311 husart->pTxBuffPtr += 2U;
2313 else
2315 husart->Instance->TDR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)uhMask);
2317 husart->TxXferCount--;
2319 /* Check the latest data transmitted */
2320 if(husart->TxXferCount == 0U)
2322 __HAL_USART_DISABLE_IT(husart, USART_IT_TXE);
2327 if(husart->RxXferCount != 0x00U)
2329 if(__HAL_USART_GET_FLAG(husart, USART_FLAG_RXNE) != RESET)
2331 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
2333 tmp = (uint16_t*) husart->pRxBuffPtr;
2334 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
2335 husart->pRxBuffPtr += 2U;
2337 else
2339 *husart->pRxBuffPtr++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
2341 husart->RxXferCount--;
2345 /* Check the latest data received */
2346 if(husart->RxXferCount == 0U)
2348 /* Disable the USART Parity Error Interrupt and RXNE interrupt*/
2349 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
2351 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2352 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
2354 /* Rx process is completed, restore husart->State to Ready */
2355 husart->State = HAL_USART_STATE_READY;
2357 HAL_USART_TxRxCpltCallback(husart);
2359 return HAL_OK;
2362 return HAL_OK;
2364 else
2366 return HAL_BUSY;
2371 * @}
2374 #endif /* HAL_USART_MODULE_ENABLED */
2376 * @}
2380 * @}
2383 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/