2 ******************************************************************************
3 * @file stm32f4xx_hal_usart.c
4 * @author MCD Application Team
7 * @brief USART HAL module driver.
8 * This file provides firmware functions to manage the following
9 * functionalities of the Universal Synchronous Asynchronous Receiver Transmitter (USART) peripheral:
10 * + Initialization and de-initialization functions
11 * + IO operation functions
12 * + Peripheral Control functions
14 ==============================================================================
15 ##### How to use this driver #####
16 ==============================================================================
18 The USART HAL driver can be used as follows:
20 (#) Declare a USART_HandleTypeDef handle structure.
21 (#) Initialize the USART low level resources by implementing the HAL_USART_MspInit () API:
22 (##) Enable the USARTx interface clock.
23 (##) USART pins configuration:
24 (+++) Enable the clock for the USART GPIOs.
25 (+++) Configure these USART pins as alternate function pull-up.
26 (##) NVIC configuration if you need to use interrupt process (HAL_USART_Transmit_IT(),
27 HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs):
28 (+++) Configure the USARTx interrupt priority.
29 (+++) Enable the NVIC USART IRQ handle.
30 (##) DMA Configuration if you need to use DMA process (HAL_USART_Transmit_DMA()
31 HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs):
32 (+++) Declare a DMA handle structure for the Tx/Rx stream.
33 (+++) Enable the DMAx interface clock.
34 (+++) Configure the declared DMA handle structure with the required Tx/Rx parameters.
35 (+++) Configure the DMA Tx/Rx Stream.
36 (+++) Associate the initialized DMA handle to the USART DMA Tx/Rx handle.
37 (+++) Configure the priority and enable the NVIC for the transfer complete interrupt on the DMA Tx/Rx Stream.
39 (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware
40 flow control and Mode(Receiver/Transmitter) in the husart Init structure.
42 (#) Initialize the USART registers by calling the HAL_USART_Init() API:
43 (++) These APIs configures also the low level Hardware GPIO, CLOCK, CORTEX...etc)
44 by calling the customized HAL_USART_MspInit(&husart) API.
46 -@@- The specific USART interrupts (Transmission complete interrupt,
47 RXNE interrupt and Error Interrupts) will be managed using the macros
48 __HAL_USART_ENABLE_IT() and __HAL_USART_DISABLE_IT() inside the transmit and receive process.
50 (#) Three operation modes are available within this driver :
52 *** Polling mode IO operation ***
53 =================================
55 (+) Send an amount of data in blocking mode using HAL_USART_Transmit()
56 (+) Receive an amount of data in blocking mode using HAL_USART_Receive()
58 *** Interrupt mode IO operation ***
59 ===================================
61 (+) Send an amount of data in non blocking mode using HAL_USART_Transmit_IT()
62 (+) At transmission end of transfer HAL_USART_TxHalfCpltCallback is executed and user can
63 add his own code by customization of function pointer HAL_USART_TxCpltCallback
64 (+) Receive an amount of data in non blocking mode using HAL_USART_Receive_IT()
65 (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can
66 add his own code by customization of function pointer HAL_USART_RxCpltCallback
67 (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can
68 add his own code by customization of function pointer HAL_USART_ErrorCallback
70 *** DMA mode IO operation ***
71 ==============================
73 (+) Send an amount of data in non blocking mode (DMA) using HAL_USART_Transmit_DMA()
74 (+) At transmission end of half transfer HAL_USART_TxHalfCpltCallback is executed and user can
75 add his own code by customization of function pointer HAL_USART_TxHalfCpltCallback
76 (+) At transmission end of transfer HAL_USART_TxCpltCallback is executed and user can
77 add his own code by customization of function pointer HAL_USART_TxCpltCallback
78 (+) Receive an amount of data in non blocking mode (DMA) using HAL_USART_Receive_DMA()
79 (+) At reception end of half transfer HAL_USART_RxHalfCpltCallback is executed and user can
80 add his own code by customization of function pointer HAL_USART_RxHalfCpltCallback
81 (+) At reception end of transfer HAL_USART_RxCpltCallback is executed and user can
82 add his own code by customization of function pointer HAL_USART_RxCpltCallback
83 (+) In case of transfer Error, HAL_USART_ErrorCallback() function is executed and user can
84 add his own code by customization of function pointer HAL_USART_ErrorCallback
85 (+) Pause the DMA Transfer using HAL_USART_DMAPause()
86 (+) Resume the DMA Transfer using HAL_USART_DMAResume()
87 (+) Stop the DMA Transfer using HAL_USART_DMAStop()
89 *** USART HAL driver macros list ***
90 =============================================
92 Below the list of most used macros in USART HAL driver.
94 (+) __HAL_USART_ENABLE: Enable the USART peripheral
95 (+) __HAL_USART_DISABLE: Disable the USART peripheral
96 (+) __HAL_USART_GET_FLAG : Check whether the specified USART flag is set or not
97 (+) __HAL_USART_CLEAR_FLAG : Clear the specified USART pending flag
98 (+) __HAL_USART_ENABLE_IT: Enable the specified USART interrupt
99 (+) __HAL_USART_DISABLE_IT: Disable the specified USART interrupt
102 (@) You can refer to the USART HAL driver header file for more useful macros
105 ******************************************************************************
108 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
110 * Redistribution and use in source and binary forms, with or without modification,
111 * are permitted provided that the following conditions are met:
112 * 1. Redistributions of source code must retain the above copyright notice,
113 * this list of conditions and the following disclaimer.
114 * 2. Redistributions in binary form must reproduce the above copyright notice,
115 * this list of conditions and the following disclaimer in the documentation
116 * and/or other materials provided with the distribution.
117 * 3. Neither the name of STMicroelectronics nor the names of its contributors
118 * may be used to endorse or promote products derived from this software
119 * without specific prior written permission.
121 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
122 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
123 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
124 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
125 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
126 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
127 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
128 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
129 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
130 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
132 ******************************************************************************
135 /* Includes ------------------------------------------------------------------*/
136 #include "stm32f4xx_hal.h"
138 /** @addtogroup STM32F4xx_HAL_Driver
142 /** @defgroup USART USART
143 * @brief HAL USART Synchronous module driver
146 #ifdef HAL_USART_MODULE_ENABLED
147 /* Private typedef -----------------------------------------------------------*/
148 /* Private define ------------------------------------------------------------*/
149 /** @addtogroup USART_Private_Constants
152 #define DUMMY_DATA 0xFFFFU
153 #define USART_TIMEOUT_VALUE 22000U
157 /* Private macro -------------------------------------------------------------*/
158 /* Private variables ---------------------------------------------------------*/
159 /* Private function prototypes -----------------------------------------------*/
160 /* Private functions ---------------------------------------------------------*/
161 /** @addtogroup USART_Private_Functions
164 static void USART_EndTxTransfer(USART_HandleTypeDef
*husart
);
165 static void USART_EndRxTransfer(USART_HandleTypeDef
*husart
);
166 static HAL_StatusTypeDef
USART_Transmit_IT(USART_HandleTypeDef
*husart
);
167 static HAL_StatusTypeDef
USART_EndTransmit_IT(USART_HandleTypeDef
*husart
);
168 static HAL_StatusTypeDef
USART_Receive_IT(USART_HandleTypeDef
*husart
);
169 static HAL_StatusTypeDef
USART_TransmitReceive_IT(USART_HandleTypeDef
*husart
);
170 static void USART_SetConfig (USART_HandleTypeDef
*husart
);
171 static void USART_DMATransmitCplt(DMA_HandleTypeDef
*hdma
);
172 static void USART_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
);
173 static void USART_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
);
174 static void USART_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
);
175 static void USART_DMAError(DMA_HandleTypeDef
*hdma
);
176 static void USART_DMAAbortOnError(DMA_HandleTypeDef
*hdma
);
177 static void USART_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
);
178 static void USART_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
);
180 static HAL_StatusTypeDef
USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef
*husart
, uint32_t Flag
, FlagStatus Status
, uint32_t Tickstart
, uint32_t Timeout
);
185 /* Exported functions --------------------------------------------------------*/
186 /** @defgroup USART_Exported_Functions USART Exported Functions
190 /** @defgroup USART_Exported_Functions_Group1 USART Initialization and de-initialization functions
191 * @brief Initialization and Configuration functions
194 ==============================================================================
195 ##### Initialization and Configuration functions #####
196 ==============================================================================
198 This subsection provides a set of functions allowing to initialize the USART
199 in asynchronous and in synchronous modes.
200 (+) For the asynchronous mode only these parameters can be configured:
204 (++) Parity: If the parity is enabled, then the MSB bit of the data written
205 in the data register is transmitted but is changed by the parity bit.
206 Depending on the frame length defined by the M bit (8-bits or 9-bits),
207 please refer to Reference manual for possible USART frame formats.
211 (++) Receiver/transmitter modes
214 The HAL_USART_Init() function follows the USART synchronous configuration
215 procedure (details for the procedure are available in reference manual (RM0329)).
222 * @brief Initializes the USART mode according to the specified
223 * parameters in the USART_InitTypeDef and create the associated handle.
224 * @param husart: pointer to a USART_HandleTypeDef structure that contains
225 * the configuration information for the specified USART module.
228 HAL_StatusTypeDef
HAL_USART_Init(USART_HandleTypeDef
*husart
)
230 /* Check the USART handle allocation */
236 /* Check the parameters */
237 assert_param(IS_USART_INSTANCE(husart
->Instance
));
239 if(husart
->State
== HAL_USART_STATE_RESET
)
241 /* Allocate lock resource and initialize it */
242 husart
->Lock
= HAL_UNLOCKED
;
243 /* Init the low level hardware */
244 HAL_USART_MspInit(husart
);
247 husart
->State
= HAL_USART_STATE_BUSY
;
249 /* Set the USART Communication parameters */
250 USART_SetConfig(husart
);
252 /* In USART mode, the following bits must be kept cleared:
253 - LINEN bit in the USART_CR2 register
254 - HDSEL, SCEN and IREN bits in the USART_CR3 register */
255 CLEAR_BIT(husart
->Instance
->CR2
, USART_CR2_LINEN
);
256 CLEAR_BIT(husart
->Instance
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
| USART_CR3_IREN
));
258 /* Enable the Peripheral */
259 __HAL_USART_ENABLE(husart
);
261 /* Initialize the USART state */
262 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
263 husart
->State
= HAL_USART_STATE_READY
;
269 * @brief DeInitializes the USART peripheral.
270 * @param husart: pointer to a USART_HandleTypeDef structure that contains
271 * the configuration information for the specified USART module.
274 HAL_StatusTypeDef
HAL_USART_DeInit(USART_HandleTypeDef
*husart
)
276 /* Check the USART handle allocation */
282 /* Check the parameters */
283 assert_param(IS_USART_INSTANCE(husart
->Instance
));
285 husart
->State
= HAL_USART_STATE_BUSY
;
287 /* Disable the Peripheral */
288 __HAL_USART_DISABLE(husart
);
290 /* DeInit the low level hardware */
291 HAL_USART_MspDeInit(husart
);
293 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
294 husart
->State
= HAL_USART_STATE_RESET
;
297 __HAL_UNLOCK(husart
);
303 * @brief USART MSP Init.
304 * @param husart: pointer to a USART_HandleTypeDef structure that contains
305 * the configuration information for the specified USART module.
308 __weak
void HAL_USART_MspInit(USART_HandleTypeDef
*husart
)
310 /* Prevent unused argument(s) compilation warning */
312 /* NOTE: This function Should not be modified, when the callback is needed,
313 the HAL_USART_MspInit could be implemented in the user file
318 * @brief USART MSP DeInit.
319 * @param husart: pointer to a USART_HandleTypeDef structure that contains
320 * the configuration information for the specified USART module.
323 __weak
void HAL_USART_MspDeInit(USART_HandleTypeDef
*husart
)
325 /* Prevent unused argument(s) compilation warning */
327 /* NOTE: This function Should not be modified, when the callback is needed,
328 the HAL_USART_MspDeInit could be implemented in the user file
336 /** @defgroup USART_Exported_Functions_Group2 IO operation functions
337 * @brief USART Transmit and Receive functions
340 ==============================================================================
341 ##### IO operation functions #####
342 ==============================================================================
344 This subsection provides a set of functions allowing to manage the USART synchronous
348 The USART supports master mode only: it cannot receive or send data related to an input
349 clock (SCLK is always an output).
351 (#) There are two modes of transfer:
352 (++) Blocking mode: The communication is performed in polling mode.
353 The HAL status of all data processing is returned by the same function
354 after finishing transfer.
355 (++) No-Blocking mode: The communication is performed using Interrupts
356 or DMA, These API's return the HAL status.
357 The end of the data processing will be indicated through the
358 dedicated USART IRQ when using Interrupt mode or the DMA IRQ when
360 The HAL_USART_TxCpltCallback(), HAL_USART_RxCpltCallback() and HAL_USART_TxRxCpltCallback()
362 will be executed respectively at the end of the transmit or Receive process
363 The HAL_USART_ErrorCallback() user callback will be executed when a communication
366 (#) Blocking mode APIs are :
367 (++) HAL_USART_Transmit() in simplex mode
368 (++) HAL_USART_Receive() in full duplex receive only
369 (++) HAL_USART_TransmitReceive() in full duplex mode
371 (#) Non Blocking mode APIs with Interrupt are :
372 (++) HAL_USART_Transmit_IT()in simplex mode
373 (++) HAL_USART_Receive_IT() in full duplex receive only
374 (++) HAL_USART_TransmitReceive_IT() in full duplex mode
375 (++) HAL_USART_IRQHandler()
377 (#) Non Blocking mode functions with DMA are :
378 (++) HAL_USART_Transmit_DMA()in simplex mode
379 (++) HAL_USART_Receive_DMA() in full duplex receive only
380 (++) HAL_USART_TransmitReceie_DMA() in full duplex mode
381 (++) HAL_USART_DMAPause()
382 (++) HAL_USART_DMAResume()
383 (++) HAL_USART_DMAStop()
385 (#) A set of Transfer Complete Callbacks are provided in non Blocking mode:
386 (++) HAL_USART_TxHalfCpltCallback()
387 (++) HAL_USART_TxCpltCallback()
388 (++) HAL_USART_RxHalfCpltCallback()
389 (++) HAL_USART_RxCpltCallback()
390 (++) HAL_USART_ErrorCallback()
391 (++) HAL_USART_TxRxCpltCallback()
398 * @brief Simplex Send an amount of data in blocking mode.
399 * @param husart: pointer to a USART_HandleTypeDef structure that contains
400 * the configuration information for the specified USART module.
401 * @param pTxData: Pointer to data buffer
402 * @param Size: Amount of data to be sent
403 * @param Timeout: Timeout duration
406 HAL_StatusTypeDef
HAL_USART_Transmit(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint16_t Size
, uint32_t Timeout
)
409 uint32_t tickstart
= 0U;
411 if(husart
->State
== HAL_USART_STATE_READY
)
413 if((pTxData
== NULL
) || (Size
== 0))
421 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
422 husart
->State
= HAL_USART_STATE_BUSY_TX
;
424 /* Init tickstart for timeout managment */
425 tickstart
= HAL_GetTick();
427 husart
->TxXferSize
= Size
;
428 husart
->TxXferCount
= Size
;
429 while(husart
->TxXferCount
> 0U)
431 husart
->TxXferCount
--;
432 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
434 /* Wait for TC flag in order to write data in DR */
435 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
439 tmp
= (uint16_t*) pTxData
;
440 husart
->Instance
->DR
= (*tmp
& (uint16_t)0x01FF);
441 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
452 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
456 husart
->Instance
->DR
= (*pTxData
++ & (uint8_t)0xFF);
460 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TC
, RESET
, tickstart
, Timeout
) != HAL_OK
)
465 husart
->State
= HAL_USART_STATE_READY
;
467 /* Process Unlocked */
468 __HAL_UNLOCK(husart
);
479 * @brief Full-Duplex Receive an amount of data in blocking mode.
480 * @param husart: pointer to a USART_HandleTypeDef structure that contains
481 * the configuration information for the specified USART module.
482 * @param pRxData: Pointer to data buffer
483 * @param Size: Amount of data to be received
484 * @param Timeout: Timeout duration
487 HAL_StatusTypeDef
HAL_USART_Receive(USART_HandleTypeDef
*husart
, uint8_t *pRxData
, uint16_t Size
, uint32_t Timeout
)
490 uint32_t tickstart
= 0U;
492 if(husart
->State
== HAL_USART_STATE_READY
)
494 if((pRxData
== NULL
) || (Size
== 0))
501 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
502 husart
->State
= HAL_USART_STATE_BUSY_RX
;
504 /* Init tickstart for timeout managment */
505 tickstart
= HAL_GetTick();
507 husart
->RxXferSize
= Size
;
508 husart
->RxXferCount
= Size
;
509 /* Check the remain data to be received */
510 while(husart
->RxXferCount
> 0U)
512 husart
->RxXferCount
--;
513 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
515 /* Wait until TXE flag is set to send dummy byte in order to generate the clock for the slave to send data */
516 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
520 /* Send dummy byte in order to generate clock */
521 husart
->Instance
->DR
= (DUMMY_DATA
& (uint16_t)0x01FF);
523 /* Wait for RXNE Flag */
524 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
528 tmp
= (uint16_t*) pRxData
;
529 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
531 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x01FF);
536 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x00FF);
542 /* Wait until TXE flag is set to send dummy byte in order to generate the clock for the slave to send data */
543 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
548 /* Send Dummy Byte in order to generate clock */
549 husart
->Instance
->DR
= (DUMMY_DATA
& (uint16_t)0x00FF);
551 /* Wait until RXNE flag is set to receive the byte */
552 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
556 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
559 *pRxData
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x00FF);
564 *pRxData
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x007F);
570 husart
->State
= HAL_USART_STATE_READY
;
572 /* Process Unlocked */
573 __HAL_UNLOCK(husart
);
584 * @brief Full-Duplex Send receive an amount of data in full-duplex mode (blocking mode).
585 * @param husart: pointer to a USART_HandleTypeDef structure that contains
586 * the configuration information for the specified USART module.
587 * @param pTxData: Pointer to data transmitted buffer
588 * @param pRxData: Pointer to data received buffer
589 * @param Size: Amount of data to be sent
590 * @param Timeout: Timeout duration
593 HAL_StatusTypeDef
HAL_USART_TransmitReceive(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
, uint32_t Timeout
)
596 uint32_t tickstart
= 0U;
598 if(husart
->State
== HAL_USART_STATE_READY
)
600 if((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0))
607 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
608 husart
->State
= HAL_USART_STATE_BUSY_RX
;
610 /* Init tickstart for timeout managment */
611 tickstart
= HAL_GetTick();
613 husart
->RxXferSize
= Size
;
614 husart
->TxXferSize
= Size
;
615 husart
->TxXferCount
= Size
;
616 husart
->RxXferCount
= Size
;
618 /* Check the remain data to be received */
619 while(husart
->TxXferCount
> 0U)
621 husart
->TxXferCount
--;
622 husart
->RxXferCount
--;
623 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
625 /* Wait for TC flag in order to write data in DR */
626 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
630 tmp
= (uint16_t*) pTxData
;
631 husart
->Instance
->DR
= (*tmp
& (uint16_t)0x01FF);
632 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
641 /* Wait for RXNE Flag */
642 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
646 tmp
= (uint16_t*) pRxData
;
647 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
649 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x01FF);
654 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x00FF);
660 /* Wait for TC flag in order to write data in DR */
661 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_TXE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
665 husart
->Instance
->DR
= (*pTxData
++ & (uint8_t)0x00FF);
667 /* Wait for RXNE Flag */
668 if(USART_WaitOnFlagUntilTimeout(husart
, USART_FLAG_RXNE
, RESET
, tickstart
, Timeout
) != HAL_OK
)
672 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
675 *pRxData
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x00FF);
680 *pRxData
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x007F);
685 husart
->State
= HAL_USART_STATE_READY
;
687 /* Process Unlocked */
688 __HAL_UNLOCK(husart
);
699 * @brief Simplex Send an amount of data in non-blocking mode.
700 * @param husart: pointer to a USART_HandleTypeDef structure that contains
701 * the configuration information for the specified USART module.
702 * @param pTxData: Pointer to data buffer
703 * @param Size: Amount of data to be sent
705 * @note The USART errors are not managed to avoid the overrun error.
707 HAL_StatusTypeDef
HAL_USART_Transmit_IT(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint16_t Size
)
709 if(husart
->State
== HAL_USART_STATE_READY
)
711 if((pTxData
== NULL
) || (Size
== 0))
719 husart
->pTxBuffPtr
= pTxData
;
720 husart
->TxXferSize
= Size
;
721 husart
->TxXferCount
= Size
;
723 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
724 husart
->State
= HAL_USART_STATE_BUSY_TX
;
726 /* The USART Error Interrupts: (Frame error, Noise error, Overrun error)
727 are not managed by the USART transmit process to avoid the overrun interrupt
728 when the USART mode is configured for transmit and receive "USART_MODE_TX_RX"
729 to benefit for the frame error and noise interrupts the USART mode should be
730 configured only for transmit "USART_MODE_TX"
731 The __HAL_USART_ENABLE_IT(husart, USART_IT_ERR) can be used to enable the Frame error,
732 Noise error interrupt */
734 /* Process Unlocked */
735 __HAL_UNLOCK(husart
);
737 /* Enable the USART Transmit Data Register Empty Interrupt */
738 SET_BIT(husart
->Instance
->CR1
, USART_CR1_TXEIE
);
749 * @brief Simplex Receive an amount of data in non-blocking mode.
750 * @param husart: pointer to a USART_HandleTypeDef structure that contains
751 * the configuration information for the specified USART module.
752 * @param pRxData: Pointer to data buffer
753 * @param Size: Amount of data to be received
756 HAL_StatusTypeDef
HAL_USART_Receive_IT(USART_HandleTypeDef
*husart
, uint8_t *pRxData
, uint16_t Size
)
758 if(husart
->State
== HAL_USART_STATE_READY
)
760 if((pRxData
== NULL
) || (Size
== 0))
767 husart
->pRxBuffPtr
= pRxData
;
768 husart
->RxXferSize
= Size
;
769 husart
->RxXferCount
= Size
;
771 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
772 husart
->State
= HAL_USART_STATE_BUSY_RX
;
774 /* Process Unlocked */
775 __HAL_UNLOCK(husart
);
777 /* Enable the USART Parity Error and Data Register not empty Interrupts */
778 SET_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
| USART_CR1_RXNEIE
);
780 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
781 SET_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
783 /* Send dummy byte in order to generate the clock for the slave to send data */
784 husart
->Instance
->DR
= (DUMMY_DATA
& (uint16_t)0x01FF);
795 * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking).
796 * @param husart: pointer to a USART_HandleTypeDef structure that contains
797 * the configuration information for the specified USART module.
798 * @param pTxData: Pointer to data transmitted buffer
799 * @param pRxData: Pointer to data received buffer
800 * @param Size: Amount of data to be received
803 HAL_StatusTypeDef
HAL_USART_TransmitReceive_IT(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
)
805 if(husart
->State
== HAL_USART_STATE_READY
)
807 if((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0))
814 husart
->pRxBuffPtr
= pRxData
;
815 husart
->RxXferSize
= Size
;
816 husart
->RxXferCount
= Size
;
817 husart
->pTxBuffPtr
= pTxData
;
818 husart
->TxXferSize
= Size
;
819 husart
->TxXferCount
= Size
;
821 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
822 husart
->State
= HAL_USART_STATE_BUSY_TX_RX
;
824 /* Process Unlocked */
825 __HAL_UNLOCK(husart
);
827 /* Enable the USART Data Register not empty Interrupt */
828 SET_BIT(husart
->Instance
->CR1
, USART_CR1_RXNEIE
);
830 /* Enable the USART Parity Error Interrupt */
831 SET_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
833 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
834 SET_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
836 /* Enable the USART Transmit Data Register Empty Interrupt */
837 SET_BIT(husart
->Instance
->CR1
, USART_CR1_TXEIE
);
848 * @brief Simplex Send an amount of data in non-blocking mode.
849 * @param husart: pointer to a USART_HandleTypeDef structure that contains
850 * the configuration information for the specified USART module.
851 * @param pTxData: Pointer to data buffer
852 * @param Size: Amount of data to be sent
855 HAL_StatusTypeDef
HAL_USART_Transmit_DMA(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint16_t Size
)
859 if(husart
->State
== HAL_USART_STATE_READY
)
861 if((pTxData
== NULL
) || (Size
== 0))
868 husart
->pTxBuffPtr
= pTxData
;
869 husart
->TxXferSize
= Size
;
870 husart
->TxXferCount
= Size
;
872 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
873 husart
->State
= HAL_USART_STATE_BUSY_TX
;
875 /* Set the USART DMA transfer complete callback */
876 husart
->hdmatx
->XferCpltCallback
= USART_DMATransmitCplt
;
878 /* Set the USART DMA Half transfer complete callback */
879 husart
->hdmatx
->XferHalfCpltCallback
= USART_DMATxHalfCplt
;
881 /* Set the DMA error callback */
882 husart
->hdmatx
->XferErrorCallback
= USART_DMAError
;
884 /* Set the DMA abort callback */
885 husart
->hdmatx
->XferAbortCallback
= NULL
;
887 /* Enable the USART transmit DMA Stream */
888 tmp
= (uint32_t*)&pTxData
;
889 HAL_DMA_Start_IT(husart
->hdmatx
, *(uint32_t*)tmp
, (uint32_t)&husart
->Instance
->DR
, Size
);
891 /* Clear the TC flag in the SR register by writing 0 to it */
892 __HAL_USART_CLEAR_FLAG(husart
, USART_FLAG_TC
);
894 /* Process Unlocked */
895 __HAL_UNLOCK(husart
);
897 /* Enable the DMA transfer for transmit request by setting the DMAT bit
898 in the USART CR3 register */
899 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
910 * @brief Full-Duplex Receive an amount of data in non-blocking mode.
911 * @param husart: pointer to a USART_HandleTypeDef structure that contains
912 * the configuration information for the specified USART module.
913 * @param pRxData: Pointer to data buffer
914 * @param Size: Amount of data to be received
916 * @note The USART DMA transmit stream must be configured in order to generate the clock for the slave.
917 * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit.
919 HAL_StatusTypeDef
HAL_USART_Receive_DMA(USART_HandleTypeDef
*husart
, uint8_t *pRxData
, uint16_t Size
)
923 if(husart
->State
== HAL_USART_STATE_READY
)
925 if((pRxData
== NULL
) || (Size
== 0))
933 husart
->pRxBuffPtr
= pRxData
;
934 husart
->RxXferSize
= Size
;
935 husart
->pTxBuffPtr
= pRxData
;
936 husart
->TxXferSize
= Size
;
938 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
939 husart
->State
= HAL_USART_STATE_BUSY_RX
;
941 /* Set the USART DMA Rx transfer complete callback */
942 husart
->hdmarx
->XferCpltCallback
= USART_DMAReceiveCplt
;
944 /* Set the USART DMA Half transfer complete callback */
945 husart
->hdmarx
->XferHalfCpltCallback
= USART_DMARxHalfCplt
;
947 /* Set the USART DMA Rx transfer error callback */
948 husart
->hdmarx
->XferErrorCallback
= USART_DMAError
;
950 /* Set the DMA abort callback */
951 husart
->hdmarx
->XferAbortCallback
= NULL
;
953 /* Set the USART Tx DMA transfer complete callback as NULL because the communication closing
954 is performed in DMA reception complete callback */
955 husart
->hdmatx
->XferHalfCpltCallback
= NULL
;
956 husart
->hdmatx
->XferCpltCallback
= NULL
;
958 /* Set the DMA error callback */
959 husart
->hdmatx
->XferErrorCallback
= USART_DMAError
;
961 /* Set the DMA AbortCpltCallback */
962 husart
->hdmatx
->XferAbortCallback
= NULL
;
964 /* Enable the USART receive DMA Stream */
965 tmp
= (uint32_t*)&pRxData
;
966 HAL_DMA_Start_IT(husart
->hdmarx
, (uint32_t)&husart
->Instance
->DR
, *(uint32_t*)tmp
, Size
);
968 /* Enable the USART transmit DMA Stream: the transmit stream is used in order
969 to generate in the non-blocking mode the clock to the slave device,
970 this mode isn't a simplex receive mode but a full-duplex receive one */
971 HAL_DMA_Start_IT(husart
->hdmatx
, *(uint32_t*)tmp
, (uint32_t)&husart
->Instance
->DR
, Size
);
973 /* Clear the Overrun flag just before enabling the DMA Rx request: mandatory for the second transfer */
974 __HAL_USART_CLEAR_OREFLAG(husart
);
976 /* Process Unlocked */
977 __HAL_UNLOCK(husart
);
979 /* Enable the USART Parity Error Interrupt */
980 SET_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
982 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
983 SET_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
985 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
986 in the USART CR3 register */
987 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
989 /* Enable the DMA transfer for transmit request by setting the DMAT bit
990 in the USART CR3 register */
991 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1002 * @brief Full-Duplex Transmit Receive an amount of data in non-blocking mode.
1003 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1004 * the configuration information for the specified USART module.
1005 * @param pTxData: Pointer to data transmitted buffer
1006 * @param pRxData: Pointer to data received buffer
1007 * @param Size: Amount of data to be received
1008 * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit.
1009 * @retval HAL status
1011 HAL_StatusTypeDef
HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef
*husart
, uint8_t *pTxData
, uint8_t *pRxData
, uint16_t Size
)
1015 if(husart
->State
== HAL_USART_STATE_READY
)
1017 if((pTxData
== NULL
) || (pRxData
== NULL
) || (Size
== 0))
1021 /* Process Locked */
1024 husart
->pRxBuffPtr
= pRxData
;
1025 husart
->RxXferSize
= Size
;
1026 husart
->pTxBuffPtr
= pTxData
;
1027 husart
->TxXferSize
= Size
;
1029 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1030 husart
->State
= HAL_USART_STATE_BUSY_TX_RX
;
1032 /* Set the USART DMA Rx transfer complete callback */
1033 husart
->hdmarx
->XferCpltCallback
= USART_DMAReceiveCplt
;
1035 /* Set the USART DMA Half transfer complete callback */
1036 husart
->hdmarx
->XferHalfCpltCallback
= USART_DMARxHalfCplt
;
1038 /* Set the USART DMA Tx transfer complete callback */
1039 husart
->hdmatx
->XferCpltCallback
= USART_DMATransmitCplt
;
1041 /* Set the USART DMA Half transfer complete callback */
1042 husart
->hdmatx
->XferHalfCpltCallback
= USART_DMATxHalfCplt
;
1044 /* Set the USART DMA Tx transfer error callback */
1045 husart
->hdmatx
->XferErrorCallback
= USART_DMAError
;
1047 /* Set the USART DMA Rx transfer error callback */
1048 husart
->hdmarx
->XferErrorCallback
= USART_DMAError
;
1050 /* Set the DMA abort callback */
1051 husart
->hdmarx
->XferAbortCallback
= NULL
;
1053 /* Enable the USART receive DMA Stream */
1054 tmp
= (uint32_t*)&pRxData
;
1055 HAL_DMA_Start_IT(husart
->hdmarx
, (uint32_t)&husart
->Instance
->DR
, *(uint32_t*)tmp
, Size
);
1057 /* Enable the USART transmit DMA Stream */
1058 tmp
= (uint32_t*)&pTxData
;
1059 HAL_DMA_Start_IT(husart
->hdmatx
, *(uint32_t*)tmp
, (uint32_t)&husart
->Instance
->DR
, Size
);
1061 /* Clear the TC flag in the SR register by writing 0 to it */
1062 __HAL_USART_CLEAR_FLAG(husart
, USART_FLAG_TC
);
1064 /* Clear the Overrun flag: mandatory for the second transfer in circular mode */
1065 __HAL_USART_CLEAR_OREFLAG(husart
);
1067 /* Process Unlocked */
1068 __HAL_UNLOCK(husart
);
1070 /* Enable the USART Parity Error Interrupt */
1071 SET_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
1073 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1074 SET_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1076 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
1077 in the USART CR3 register */
1078 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1080 /* Enable the DMA transfer for transmit request by setting the DMAT bit
1081 in the USART CR3 register */
1082 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1093 * @brief Pauses the DMA Transfer.
1094 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1095 * the configuration information for the specified USART module.
1096 * @retval HAL status
1098 HAL_StatusTypeDef
HAL_USART_DMAPause(USART_HandleTypeDef
*husart
)
1100 /* Process Locked */
1103 /* Disable the USART DMA Tx request */
1104 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1106 /* Process Unlocked */
1107 __HAL_UNLOCK(husart
);
1113 * @brief Resumes the DMA Transfer.
1114 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1115 * the configuration information for the specified USART module.
1116 * @retval HAL status
1118 HAL_StatusTypeDef
HAL_USART_DMAResume(USART_HandleTypeDef
*husart
)
1120 /* Process Locked */
1123 /* Enable the USART DMA Tx request */
1124 SET_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1126 /* Process Unlocked */
1127 __HAL_UNLOCK(husart
);
1133 * @brief Stops the DMA Transfer.
1134 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1135 * the configuration information for the specified USART module.
1136 * @retval HAL status
1138 HAL_StatusTypeDef
HAL_USART_DMAStop(USART_HandleTypeDef
*husart
)
1140 uint32_t dmarequest
= 0x00U
;
1141 /* The Lock is not implemented on this API to allow the user application
1142 to call the HAL USART API under callbacks HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback():
1143 when calling HAL_DMA_Abort() API the DMA TX/RX Transfer complete interrupt is generated
1144 and the correspond call back is executed HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback()
1147 /* Stop USART DMA Tx request if ongoing */
1148 dmarequest
= HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1149 if((husart
->State
== HAL_USART_STATE_BUSY_TX
) && dmarequest
)
1151 USART_EndTxTransfer(husart
);
1153 /* Abort the USART DMA Tx channel */
1154 if(husart
->hdmatx
!= NULL
)
1156 HAL_DMA_Abort(husart
->hdmatx
);
1159 /* Disable the USART Tx DMA request */
1160 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1163 /* Stop USART DMA Rx request if ongoing */
1164 dmarequest
= HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1165 if((husart
->State
== HAL_USART_STATE_BUSY_RX
) && dmarequest
)
1167 USART_EndRxTransfer(husart
);
1169 /* Abort the USART DMA Rx channel */
1170 if(husart
->hdmarx
!= NULL
)
1172 HAL_DMA_Abort(husart
->hdmarx
);
1175 /* Disable the USART Rx DMA request */
1176 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1183 * @brief Abort ongoing transfer (blocking mode).
1184 * @param husart USART handle.
1185 * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx,
1186 * as described by TransferType parameter) started in Interrupt or DMA mode.
1187 * This procedure performs following operations :
1188 * - Disable PPP Interrupts (depending of transfer direction)
1189 * - Disable the DMA transfer in the peripheral register (if enabled)
1190 * - Abort DMA transfer by calling HAL_DMA_Abort (in case of transfer in DMA mode)
1191 * - Set handle State to READY
1192 * @note This procedure is executed in blocking mode : when exiting function, Abort is considered as completed.
1193 * @retval HAL status
1195 HAL_StatusTypeDef
HAL_USART_Abort(USART_HandleTypeDef
*husart
)
1197 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1198 CLEAR_BIT(husart
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
| USART_CR1_TXEIE
| USART_CR1_TCIE
));
1199 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1201 /* Disable the USART DMA Tx request if enabled */
1202 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAT
))
1204 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1206 /* Abort the USART DMA Tx channel : use blocking DMA Abort API (no callback) */
1207 if(husart
->hdmatx
!= NULL
)
1209 /* Set the USART DMA Abort callback to Null.
1210 No call back execution at end of DMA abort procedure */
1211 husart
->hdmatx
->XferAbortCallback
= NULL
;
1213 HAL_DMA_Abort(husart
->hdmatx
);
1217 /* Disable the USART DMA Rx request if enabled */
1218 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
))
1220 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1222 /* Abort the USART DMA Rx channel : use blocking DMA Abort API (no callback) */
1223 if(husart
->hdmarx
!= NULL
)
1225 /* Set the USART DMA Abort callback to Null.
1226 No call back execution at end of DMA abort procedure */
1227 husart
->hdmarx
->XferAbortCallback
= NULL
;
1229 HAL_DMA_Abort(husart
->hdmarx
);
1233 /* Reset Tx and Rx transfer counters */
1234 husart
->TxXferCount
= 0x00U
;
1235 husart
->RxXferCount
= 0x00U
;
1237 /* Restore husart->State to Ready */
1238 husart
->State
= HAL_USART_STATE_READY
;
1240 /* Reset Handle ErrorCode to No Error */
1241 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1247 * @brief Abort ongoing transfer (Interrupt mode).
1248 * @param husart USART handle.
1249 * @note This procedure could be used for aborting any ongoing transfer (either Tx or Rx,
1250 * as described by TransferType parameter) started in Interrupt or DMA mode.
1251 * This procedure performs following operations :
1252 * - Disable PPP Interrupts (depending of transfer direction)
1253 * - Disable the DMA transfer in the peripheral register (if enabled)
1254 * - Abort DMA transfer by calling HAL_DMA_Abort_IT (in case of transfer in DMA mode)
1255 * - Set handle State to READY
1256 * - At abort completion, call user abort complete callback
1257 * @note This procedure is executed in Interrupt mode, meaning that abort procedure could be
1258 * considered as completed only when user abort complete callback is executed (not when exiting function).
1259 * @retval HAL status
1261 HAL_StatusTypeDef
HAL_USART_Abort_IT(USART_HandleTypeDef
*husart
)
1263 uint32_t AbortCplt
= 0x01U
;
1265 /* Disable TXEIE, TCIE, RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1266 CLEAR_BIT(husart
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
| USART_CR1_TXEIE
| USART_CR1_TCIE
));
1267 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1269 /* If DMA Tx and/or DMA Rx Handles are associated to USART Handle, DMA Abort complete callbacks should be initialised
1270 before any call to DMA Abort functions */
1271 /* DMA Tx Handle is valid */
1272 if(husart
->hdmatx
!= NULL
)
1274 /* Set DMA Abort Complete callback if USART DMA Tx request if enabled.
1275 Otherwise, set it to NULL */
1276 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAT
))
1278 husart
->hdmatx
->XferAbortCallback
= USART_DMATxAbortCallback
;
1282 husart
->hdmatx
->XferAbortCallback
= NULL
;
1285 /* DMA Rx Handle is valid */
1286 if(husart
->hdmarx
!= NULL
)
1288 /* Set DMA Abort Complete callback if USART DMA Rx request if enabled.
1289 Otherwise, set it to NULL */
1290 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
))
1292 husart
->hdmarx
->XferAbortCallback
= USART_DMARxAbortCallback
;
1296 husart
->hdmarx
->XferAbortCallback
= NULL
;
1300 /* Disable the USART DMA Tx request if enabled */
1301 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAT
))
1303 /* Disable DMA Tx at USART level */
1304 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1306 /* Abort the USART DMA Tx channel : use non blocking DMA Abort API (callback) */
1307 if(husart
->hdmatx
!= NULL
)
1309 /* USART Tx DMA Abort callback has already been initialised :
1310 will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */
1313 if(HAL_DMA_Abort_IT(husart
->hdmatx
) != HAL_OK
)
1315 husart
->hdmatx
->XferAbortCallback
= NULL
;
1324 /* Disable the USART DMA Rx request if enabled */
1325 if(HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
))
1327 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1329 /* Abort the USART DMA Rx channel : use non blocking DMA Abort API (callback) */
1330 if(husart
->hdmarx
!= NULL
)
1332 /* USART Rx DMA Abort callback has already been initialised :
1333 will lead to call HAL_USART_AbortCpltCallback() at end of DMA abort procedure */
1336 if(HAL_DMA_Abort_IT(husart
->hdmarx
) != HAL_OK
)
1338 husart
->hdmarx
->XferAbortCallback
= NULL
;
1348 /* if no DMA abort complete callback execution is required => call user Abort Complete callback */
1349 if(AbortCplt
== 0x01U
)
1351 /* Reset Tx and Rx transfer counters */
1352 husart
->TxXferCount
= 0x00U
;
1353 husart
->RxXferCount
= 0x00U
;
1355 /* Reset errorCode */
1356 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1358 /* Restore husart->State to Ready */
1359 husart
->State
= HAL_USART_STATE_READY
;
1361 /* As no DMA to be aborted, call directly user Abort complete callback */
1362 HAL_USART_AbortCpltCallback(husart
);
1369 * @brief This function handles USART interrupt request.
1370 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1371 * the configuration information for the specified USART module.
1374 void HAL_USART_IRQHandler(USART_HandleTypeDef
*husart
)
1376 uint32_t isrflags
= READ_REG(husart
->Instance
->SR
);
1377 uint32_t cr1its
= READ_REG(husart
->Instance
->CR1
);
1378 uint32_t cr3its
= READ_REG(husart
->Instance
->CR3
);
1379 uint32_t errorflags
= 0x00U
;
1380 uint32_t dmarequest
= 0x00U
;
1382 /* If no error occurs */
1383 errorflags
= (isrflags
& (uint32_t)(USART_SR_PE
| USART_SR_FE
| USART_SR_ORE
| USART_SR_NE
));
1384 if(errorflags
== RESET
)
1386 /* USART in mode Receiver -------------------------------------------------*/
1387 if(((isrflags
& USART_SR_RXNE
) != RESET
) && ((cr1its
& USART_CR1_RXNEIE
) != RESET
))
1389 if(husart
->State
== HAL_USART_STATE_BUSY_RX
)
1391 USART_Receive_IT(husart
);
1395 USART_TransmitReceive_IT(husart
);
1400 /* If some errors occur */
1401 if((errorflags
!= RESET
) && (((cr3its
& USART_CR3_EIE
) != RESET
) || ((cr1its
& (USART_CR1_RXNEIE
| USART_CR1_PEIE
)) != RESET
)))
1403 /* USART parity error interrupt occurred ----------------------------------*/
1404 if(((isrflags
& USART_SR_PE
) != RESET
) && ((cr1its
& USART_CR1_PEIE
) != RESET
))
1406 husart
->ErrorCode
|= HAL_USART_ERROR_PE
;
1409 /* USART noise error interrupt occurred --------------------------------*/
1410 if(((isrflags
& USART_SR_NE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1412 husart
->ErrorCode
|= HAL_USART_ERROR_NE
;
1415 /* USART frame error interrupt occurred --------------------------------*/
1416 if(((isrflags
& USART_SR_FE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1418 husart
->ErrorCode
|= HAL_USART_ERROR_FE
;
1421 /* USART Over-Run interrupt occurred -----------------------------------*/
1422 if(((isrflags
& USART_SR_ORE
) != RESET
) && ((cr3its
& USART_CR3_EIE
) != RESET
))
1424 husart
->ErrorCode
|= HAL_USART_ERROR_ORE
;
1427 if(husart
->ErrorCode
!= HAL_USART_ERROR_NONE
)
1429 /* USART in mode Receiver -----------------------------------------------*/
1430 if(((isrflags
& USART_SR_RXNE
) != RESET
) && ((cr1its
& USART_CR1_RXNEIE
) != RESET
))
1432 if(husart
->State
== HAL_USART_STATE_BUSY_RX
)
1434 USART_Receive_IT(husart
);
1438 USART_TransmitReceive_IT(husart
);
1441 /* If Overrun error occurs, or if any error occurs in DMA mode reception,
1442 consider error as blocking */
1443 dmarequest
= HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1444 if(((husart
->ErrorCode
& HAL_USART_ERROR_ORE
) != RESET
) || dmarequest
)
1446 /* Set the USART state ready to be able to start again the process,
1447 Disable Rx Interrupts, and disable Rx DMA request, if ongoing */
1448 USART_EndRxTransfer(husart
);
1450 /* Disable the USART DMA Rx request if enabled */
1451 if (HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
))
1453 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1455 /* Abort the USART DMA Rx channel */
1456 if(husart
->hdmarx
!= NULL
)
1458 /* Set the USART DMA Abort callback :
1459 will lead to call HAL_USART_ErrorCallback() at end of DMA abort procedure */
1460 husart
->hdmarx
->XferAbortCallback
= USART_DMAAbortOnError
;
1462 if(HAL_DMA_Abort_IT(husart
->hdmarx
) != HAL_OK
)
1464 /* Call Directly XferAbortCallback function in case of error */
1465 husart
->hdmarx
->XferAbortCallback(husart
->hdmarx
);
1470 /* Call user error callback */
1471 HAL_USART_ErrorCallback(husart
);
1476 /* Call user error callback */
1477 HAL_USART_ErrorCallback(husart
);
1482 /* Call user error callback */
1483 HAL_USART_ErrorCallback(husart
);
1484 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1490 /* USART in mode Transmitter -----------------------------------------------*/
1491 if(((isrflags
& USART_SR_TXE
) != RESET
) && ((cr1its
& USART_CR1_TXEIE
) != RESET
))
1493 if(husart
->State
== HAL_USART_STATE_BUSY_TX
)
1495 USART_Transmit_IT(husart
);
1499 USART_TransmitReceive_IT(husart
);
1504 /* USART in mode Transmitter (transmission end) ----------------------------*/
1505 if(((isrflags
& USART_SR_TC
) != RESET
) && ((cr1its
& USART_CR1_TCIE
) != RESET
))
1507 USART_EndTransmit_IT(husart
);
1513 * @brief Tx Transfer completed callbacks.
1514 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1515 * the configuration information for the specified USART module.
1518 __weak
void HAL_USART_TxCpltCallback(USART_HandleTypeDef
*husart
)
1520 /* Prevent unused argument(s) compilation warning */
1522 /* NOTE: This function Should not be modified, when the callback is needed,
1523 the HAL_USART_TxCpltCallback could be implemented in the user file
1528 * @brief Tx Half Transfer completed callbacks.
1529 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1530 * the configuration information for the specified USART module.
1533 __weak
void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef
*husart
)
1535 /* Prevent unused argument(s) compilation warning */
1537 /* NOTE: This function Should not be modified, when the callback is needed,
1538 the HAL_USART_TxCpltCallback could be implemented in the user file
1543 * @brief Rx Transfer completed callbacks.
1544 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1545 * the configuration information for the specified USART module.
1548 __weak
void HAL_USART_RxCpltCallback(USART_HandleTypeDef
*husart
)
1550 /* Prevent unused argument(s) compilation warning */
1552 /* NOTE: This function Should not be modified, when the callback is needed,
1553 the HAL_USART_TxCpltCallback could be implemented in the user file
1558 * @brief Rx Half Transfer completed callbacks.
1559 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1560 * the configuration information for the specified USART module.
1563 __weak
void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef
*husart
)
1565 /* Prevent unused argument(s) compilation warning */
1567 /* NOTE: This function Should not be modified, when the callback is needed,
1568 the HAL_USART_TxCpltCallback could be implemented in the user file
1573 * @brief Tx/Rx Transfers completed callback for the non-blocking process.
1574 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1575 * the configuration information for the specified USART module.
1578 __weak
void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef
*husart
)
1580 /* Prevent unused argument(s) compilation warning */
1582 /* NOTE: This function Should not be modified, when the callback is needed,
1583 the HAL_USART_TxCpltCallback could be implemented in the user file
1588 * @brief USART error callbacks.
1589 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1590 * the configuration information for the specified USART module.
1593 __weak
void HAL_USART_ErrorCallback(USART_HandleTypeDef
*husart
)
1595 /* Prevent unused argument(s) compilation warning */
1597 /* NOTE: This function Should not be modified, when the callback is needed,
1598 the HAL_USART_ErrorCallback could be implemented in the user file
1603 * @brief USART Abort Complete callback.
1604 * @param husart USART handle.
1607 __weak
void HAL_USART_AbortCpltCallback (USART_HandleTypeDef
*husart
)
1609 /* Prevent unused argument(s) compilation warning */
1612 /* NOTE : This function should not be modified, when the callback is needed,
1613 the HAL_USART_AbortCpltCallback can be implemented in the user file.
1621 /** @defgroup USART_Exported_Functions_Group3 Peripheral State and Errors functions
1622 * @brief USART State and Errors functions
1625 ==============================================================================
1626 ##### Peripheral State and Errors functions #####
1627 ==============================================================================
1629 This subsection provides a set of functions allowing to return the State of
1631 process, return Peripheral Errors occurred during communication process
1632 (+) HAL_USART_GetState() API can be helpful to check in run-time the state
1633 of the USART peripheral.
1634 (+) HAL_USART_GetError() check in run-time errors that could be occurred during
1641 * @brief Returns the USART state.
1642 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1643 * the configuration information for the specified USART module.
1646 HAL_USART_StateTypeDef
HAL_USART_GetState(USART_HandleTypeDef
*husart
)
1648 return husart
->State
;
1652 * @brief Return the USART error code
1653 * @param husart : pointer to a USART_HandleTypeDef structure that contains
1654 * the configuration information for the specified USART.
1655 * @retval USART Error Code
1657 uint32_t HAL_USART_GetError(USART_HandleTypeDef
*husart
)
1659 return husart
->ErrorCode
;
1667 * @brief DMA USART transmit process complete callback.
1668 * @param hdma: DMA handle
1671 static void USART_DMATransmitCplt(DMA_HandleTypeDef
*hdma
)
1673 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1674 /* DMA Normal mode */
1675 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == 0U)
1677 husart
->TxXferCount
= 0U;
1678 if(husart
->State
== HAL_USART_STATE_BUSY_TX
)
1680 /* Disable the DMA transfer for transmit request by resetting the DMAT bit
1681 in the USART CR3 register */
1682 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1684 /* Enable the USART Transmit Complete Interrupt */
1685 SET_BIT(husart
->Instance
->CR1
, USART_CR1_TCIE
);
1688 /* DMA Circular mode */
1691 if(husart
->State
== HAL_USART_STATE_BUSY_TX
)
1693 HAL_USART_TxCpltCallback(husart
);
1699 * @brief DMA USART transmit process half complete callback
1700 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1701 * the configuration information for the specified DMA module.
1704 static void USART_DMATxHalfCplt(DMA_HandleTypeDef
*hdma
)
1706 USART_HandleTypeDef
* husart
= (USART_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1708 HAL_USART_TxHalfCpltCallback(husart
);
1712 * @brief DMA USART receive process complete callback.
1713 * @param hdma: DMA handle
1716 static void USART_DMAReceiveCplt(DMA_HandleTypeDef
*hdma
)
1718 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1719 /* DMA Normal mode */
1720 if((hdma
->Instance
->CR
& DMA_SxCR_CIRC
) == 0U)
1722 husart
->RxXferCount
= 0x00U
;
1724 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1725 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
1726 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1728 if(husart
->State
== HAL_USART_STATE_BUSY_RX
)
1730 /* Disable the DMA transfer for the Transmit/receiver requests by setting the DMAT/DMAR bit
1731 in the USART CR3 register */
1732 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1734 husart
->State
= HAL_USART_STATE_READY
;
1735 HAL_USART_RxCpltCallback(husart
);
1737 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1740 /* Disable the DMA transfer for the Transmit/receiver requests by setting the DMAT/DMAR bit
1741 in the USART CR3 register */
1742 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1743 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1745 husart
->State
= HAL_USART_STATE_READY
;
1746 HAL_USART_TxRxCpltCallback(husart
);
1749 /* DMA circular mode */
1752 if(husart
->State
== HAL_USART_STATE_BUSY_RX
)
1754 HAL_USART_RxCpltCallback(husart
);
1756 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1759 HAL_USART_TxRxCpltCallback(husart
);
1765 * @brief DMA USART receive process half complete callback
1766 * @param hdma: pointer to a DMA_HandleTypeDef structure that contains
1767 * the configuration information for the specified DMA module.
1770 static void USART_DMARxHalfCplt(DMA_HandleTypeDef
*hdma
)
1772 USART_HandleTypeDef
* husart
= (USART_HandleTypeDef
*)((DMA_HandleTypeDef
*)hdma
)->Parent
;
1774 HAL_USART_RxHalfCpltCallback(husart
);
1778 * @brief DMA USART communication error callback.
1779 * @param hdma: DMA handle
1782 static void USART_DMAError(DMA_HandleTypeDef
*hdma
)
1784 uint32_t dmarequest
= 0x00U
;
1785 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1786 husart
->RxXferCount
= 0x00U
;
1787 husart
->TxXferCount
= 0x00U
;
1789 /* Stop USART DMA Tx request if ongoing */
1790 dmarequest
= HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAT
);
1791 if((husart
->State
== HAL_USART_STATE_BUSY_TX
) && dmarequest
)
1793 USART_EndTxTransfer(husart
);
1796 /* Stop USART DMA Rx request if ongoing */
1797 dmarequest
= HAL_IS_BIT_SET(husart
->Instance
->CR3
, USART_CR3_DMAR
);
1798 if((husart
->State
== HAL_USART_STATE_BUSY_RX
) && dmarequest
)
1800 USART_EndRxTransfer(husart
);
1803 husart
->ErrorCode
|= HAL_USART_ERROR_DMA
;
1804 husart
->State
= HAL_USART_STATE_READY
;
1806 HAL_USART_ErrorCallback(husart
);
1810 * @brief This function handles USART Communication Timeout.
1811 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1812 * the configuration information for the specified USART module.
1813 * @param Flag: specifies the USART flag to check.
1814 * @param Status: The new Flag status (SET or RESET).
1815 * @param Tickstart: Tick start value.
1816 * @param Timeout: Timeout duration.
1817 * @retval HAL status
1819 static HAL_StatusTypeDef
USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef
*husart
, uint32_t Flag
, FlagStatus Status
, uint32_t Tickstart
, uint32_t Timeout
)
1821 /* Wait until flag is set */
1822 while((__HAL_USART_GET_FLAG(husart
, Flag
) ? SET
: RESET
) == Status
)
1824 /* Check for the Timeout */
1825 if(Timeout
!= HAL_MAX_DELAY
)
1827 if((Timeout
== 0U)||((HAL_GetTick() - Tickstart
) > Timeout
))
1829 /* Disable the USART Transmit Complete Interrupt */
1830 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_TXEIE
);
1832 /* Disable the USART RXNE Interrupt */
1833 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_RXNEIE
);
1835 /* Disable the USART Parity Error Interrupt */
1836 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
1838 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1839 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1841 husart
->State
= HAL_USART_STATE_READY
;
1843 /* Process Unlocked */
1844 __HAL_UNLOCK(husart
);
1854 * @brief End ongoing Tx transfer on USART peripheral (following error detection or Transmit completion).
1855 * @param husart: USART handle.
1858 static void USART_EndTxTransfer(USART_HandleTypeDef
*husart
)
1860 /* Disable TXEIE and TCIE interrupts */
1861 CLEAR_BIT(husart
->Instance
->CR1
, (USART_CR1_TXEIE
| USART_CR1_TCIE
));
1863 /* At end of Tx process, restore husart->State to Ready */
1864 husart
->State
= HAL_USART_STATE_READY
;
1868 * @brief End ongoing Rx transfer on USART peripheral (following error detection or Reception completion).
1869 * @param husart: USART handle.
1872 static void USART_EndRxTransfer(USART_HandleTypeDef
*husart
)
1874 /* Disable RXNE, PE and ERR interrupts */
1875 CLEAR_BIT(husart
->Instance
->CR1
, (USART_CR1_RXNEIE
| USART_CR1_PEIE
));
1876 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
1878 /* At end of Rx process, restore husart->State to Ready */
1879 husart
->State
= HAL_USART_STATE_READY
;
1883 * @brief DMA USART communication abort callback, when initiated by HAL services on Error
1884 * (To be called at end of DMA Abort procedure following error occurrence).
1885 * @param hdma DMA handle.
1888 static void USART_DMAAbortOnError(DMA_HandleTypeDef
*hdma
)
1890 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1891 husart
->RxXferCount
= 0x00U
;
1892 husart
->TxXferCount
= 0x00U
;
1894 HAL_USART_ErrorCallback(husart
);
1898 * @brief DMA USART Tx communication abort callback, when initiated by user
1899 * (To be called at end of DMA Tx Abort procedure following user abort request).
1900 * @note When this callback is executed, User Abort complete call back is called only if no
1901 * Abort still ongoing for Rx DMA Handle.
1902 * @param hdma DMA handle.
1905 static void USART_DMATxAbortCallback(DMA_HandleTypeDef
*hdma
)
1907 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1909 husart
->hdmatx
->XferAbortCallback
= NULL
;
1911 /* Check if an Abort process is still ongoing */
1912 if(husart
->hdmarx
!= NULL
)
1914 if(husart
->hdmarx
->XferAbortCallback
!= NULL
)
1920 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1921 husart
->TxXferCount
= 0x00U
;
1922 husart
->RxXferCount
= 0x00U
;
1924 /* Reset errorCode */
1925 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1927 /* Restore husart->State to Ready */
1928 husart
->State
= HAL_USART_STATE_READY
;
1930 /* Call user Abort complete callback */
1931 HAL_USART_AbortCpltCallback(husart
);
1935 * @brief DMA USART Rx communication abort callback, when initiated by user
1936 * (To be called at end of DMA Rx Abort procedure following user abort request).
1937 * @note When this callback is executed, User Abort complete call back is called only if no
1938 * Abort still ongoing for Tx DMA Handle.
1939 * @param hdma DMA handle.
1942 static void USART_DMARxAbortCallback(DMA_HandleTypeDef
*hdma
)
1944 USART_HandleTypeDef
* husart
= ( USART_HandleTypeDef
* )((DMA_HandleTypeDef
* )hdma
)->Parent
;
1946 husart
->hdmarx
->XferAbortCallback
= NULL
;
1948 /* Check if an Abort process is still ongoing */
1949 if(husart
->hdmatx
!= NULL
)
1951 if(husart
->hdmatx
->XferAbortCallback
!= NULL
)
1957 /* No Abort process still ongoing : All DMA channels are aborted, call user Abort Complete callback */
1958 husart
->TxXferCount
= 0x00U
;
1959 husart
->RxXferCount
= 0x00U
;
1961 /* Reset errorCode */
1962 husart
->ErrorCode
= HAL_USART_ERROR_NONE
;
1964 /* Restore husart->State to Ready */
1965 husart
->State
= HAL_USART_STATE_READY
;
1967 /* Call user Abort complete callback */
1968 HAL_USART_AbortCpltCallback(husart
);
1972 * @brief Simplex Send an amount of data in non-blocking mode.
1973 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1974 * the configuration information for the specified USART module.
1975 * @retval HAL status
1976 * @note The USART errors are not managed to avoid the overrun error.
1978 static HAL_StatusTypeDef
USART_Transmit_IT(USART_HandleTypeDef
*husart
)
1982 if(husart
->State
== HAL_USART_STATE_BUSY_TX
)
1984 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
1986 tmp
= (uint16_t*) husart
->pTxBuffPtr
;
1987 husart
->Instance
->DR
= (uint16_t)(*tmp
& (uint16_t)0x01FF);
1988 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
1990 husart
->pTxBuffPtr
+= 2U;
1994 husart
->pTxBuffPtr
+= 1U;
1999 husart
->Instance
->DR
= (uint8_t)(*husart
->pTxBuffPtr
++ & (uint8_t)0x00FF);
2002 if(--husart
->TxXferCount
== 0U)
2004 /* Disable the USART Transmit data register empty Interrupt */
2005 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_TXEIE
);
2007 /* Enable the USART Transmit Complete Interrupt */
2008 SET_BIT(husart
->Instance
->CR1
, USART_CR1_TCIE
);
2019 * @brief Wraps up transmission in non blocking mode.
2020 * @param husart: pointer to a USART_HandleTypeDef structure that contains
2021 * the configuration information for the specified USART module.
2022 * @retval HAL status
2024 static HAL_StatusTypeDef
USART_EndTransmit_IT(USART_HandleTypeDef
*husart
)
2026 /* Disable the USART Transmit Complete Interrupt */
2027 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_TCIE
);
2029 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2030 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
2032 husart
->State
= HAL_USART_STATE_READY
;
2034 HAL_USART_TxCpltCallback(husart
);
2040 * @brief Simplex Receive an amount of data in non-blocking mode.
2041 * @param husart: pointer to a USART_HandleTypeDef structure that contains
2042 * the configuration information for the specified USART module.
2043 * @retval HAL status
2045 static HAL_StatusTypeDef
USART_Receive_IT(USART_HandleTypeDef
*husart
)
2048 if(husart
->State
== HAL_USART_STATE_BUSY_RX
)
2050 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
2052 tmp
= (uint16_t*) husart
->pRxBuffPtr
;
2053 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
2055 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x01FF);
2056 husart
->pRxBuffPtr
+= 2U;
2060 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x00FF);
2061 husart
->pRxBuffPtr
+= 1U;
2063 if(--husart
->RxXferCount
!= 0x00U
)
2065 /* Send dummy byte in order to generate the clock for the slave to send the next data */
2066 husart
->Instance
->DR
= (DUMMY_DATA
& (uint16_t)0x01FF);
2071 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
2073 *husart
->pRxBuffPtr
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x00FF);
2077 *husart
->pRxBuffPtr
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x007F);
2080 if(--husart
->RxXferCount
!= 0x00U
)
2082 /* Send dummy byte in order to generate the clock for the slave to send the next data */
2083 husart
->Instance
->DR
= (DUMMY_DATA
& (uint16_t)0x00FF);
2087 if(husart
->RxXferCount
== 0U)
2089 /* Disable the USART RXNE Interrupt */
2090 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_RXNEIE
);
2092 /* Disable the USART Parity Error Interrupt */
2093 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
2095 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2096 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
2098 husart
->State
= HAL_USART_STATE_READY
;
2099 HAL_USART_RxCpltCallback(husart
);
2112 * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking).
2113 * @param husart: pointer to a USART_HandleTypeDef structure that contains
2114 * the configuration information for the specified USART module.
2115 * @retval HAL status
2117 static HAL_StatusTypeDef
USART_TransmitReceive_IT(USART_HandleTypeDef
*husart
)
2121 if(husart
->State
== HAL_USART_STATE_BUSY_TX_RX
)
2123 if(husart
->TxXferCount
!= 0x00U
)
2125 if(__HAL_USART_GET_FLAG(husart
, USART_FLAG_TXE
) != RESET
)
2127 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
2129 tmp
= (uint16_t*) husart
->pTxBuffPtr
;
2130 husart
->Instance
->DR
= (uint16_t)(*tmp
& (uint16_t)0x01FF);
2131 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
2133 husart
->pTxBuffPtr
+= 2U;
2137 husart
->pTxBuffPtr
+= 1U;
2142 husart
->Instance
->DR
= (uint8_t)(*husart
->pTxBuffPtr
++ & (uint8_t)0x00FF);
2144 husart
->TxXferCount
--;
2146 /* Check the latest data transmitted */
2147 if(husart
->TxXferCount
== 0U)
2149 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_TXEIE
);
2154 if(husart
->RxXferCount
!= 0x00U
)
2156 if(__HAL_USART_GET_FLAG(husart
, USART_FLAG_RXNE
) != RESET
)
2158 if(husart
->Init
.WordLength
== USART_WORDLENGTH_9B
)
2160 tmp
= (uint16_t*) husart
->pRxBuffPtr
;
2161 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
2163 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x01FF);
2164 husart
->pRxBuffPtr
+= 2U;
2168 *tmp
= (uint16_t)(husart
->Instance
->DR
& (uint16_t)0x00FF);
2169 husart
->pRxBuffPtr
+= 1U;
2174 if(husart
->Init
.Parity
== USART_PARITY_NONE
)
2176 *husart
->pRxBuffPtr
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x00FF);
2180 *husart
->pRxBuffPtr
++ = (uint8_t)(husart
->Instance
->DR
& (uint8_t)0x007F);
2183 husart
->RxXferCount
--;
2187 /* Check the latest data received */
2188 if(husart
->RxXferCount
== 0U)
2190 /* Disable the USART RXNE Interrupt */
2191 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_RXNEIE
);
2193 /* Disable the USART Parity Error Interrupt */
2194 CLEAR_BIT(husart
->Instance
->CR1
, USART_CR1_PEIE
);
2196 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
2197 CLEAR_BIT(husart
->Instance
->CR3
, USART_CR3_EIE
);
2199 husart
->State
= HAL_USART_STATE_READY
;
2201 HAL_USART_TxRxCpltCallback(husart
);
2215 * @brief Configures the USART pferipheral.
2216 * @param husart: pointer to a USART_HandleTypeDef structure that contains
2217 * the configuration information for the specified USART module.
2220 static void USART_SetConfig(USART_HandleTypeDef
*husart
)
2222 uint32_t tmpreg
= 0x00U
;
2224 /* Check the parameters */
2225 assert_param(IS_USART_INSTANCE(husart
->Instance
));
2226 assert_param(IS_USART_POLARITY(husart
->Init
.CLKPolarity
));
2227 assert_param(IS_USART_PHASE(husart
->Init
.CLKPhase
));
2228 assert_param(IS_USART_LASTBIT(husart
->Init
.CLKLastBit
));
2229 assert_param(IS_USART_BAUDRATE(husart
->Init
.BaudRate
));
2230 assert_param(IS_USART_WORD_LENGTH(husart
->Init
.WordLength
));
2231 assert_param(IS_USART_STOPBITS(husart
->Init
.StopBits
));
2232 assert_param(IS_USART_PARITY(husart
->Init
.Parity
));
2233 assert_param(IS_USART_MODE(husart
->Init
.Mode
));
2235 /* The LBCL, CPOL and CPHA bits have to be selected when both the transmitter and the
2236 receiver are disabled (TE=RE=0) to ensure that the clock pulses function correctly. */
2237 CLEAR_BIT(husart
->Instance
->CR1
, (USART_CR1_TE
| USART_CR1_RE
));
2239 /*---------------------------- USART CR2 Configuration ---------------------*/
2240 tmpreg
= husart
->Instance
->CR2
;
2241 /* Clear CLKEN, CPOL, CPHA and LBCL bits */
2242 tmpreg
&= (uint32_t)~((uint32_t)(USART_CR2_CPHA
| USART_CR2_CPOL
| USART_CR2_CLKEN
| USART_CR2_LBCL
| USART_CR2_STOP
));
2243 /* Configure the USART Clock, CPOL, CPHA and LastBit -----------------------*/
2244 /* Set CPOL bit according to husart->Init.CLKPolarity value */
2245 /* Set CPHA bit according to husart->Init.CLKPhase value */
2246 /* Set LBCL bit according to husart->Init.CLKLastBit value */
2247 /* Set Stop Bits: Set STOP[13:12] bits according to husart->Init.StopBits value */
2248 tmpreg
|= (uint32_t)(USART_CLOCK_ENABLE
| husart
->Init
.CLKPolarity
|
2249 husart
->Init
.CLKPhase
| husart
->Init
.CLKLastBit
| husart
->Init
.StopBits
);
2250 /* Write to USART CR2 */
2251 WRITE_REG(husart
->Instance
->CR2
, (uint32_t)tmpreg
);
2253 /*-------------------------- USART CR1 Configuration -----------------------*/
2254 tmpreg
= husart
->Instance
->CR1
;
2256 /* Clear M, PCE, PS, TE, RE and OVER8 bits */
2257 tmpreg
&= (uint32_t)~((uint32_t)(USART_CR1_M
| USART_CR1_PCE
| USART_CR1_PS
| USART_CR1_TE
| \
2258 USART_CR1_RE
| USART_CR1_OVER8
));
2260 /* Configure the USART Word Length, Parity and mode:
2261 Set the M bits according to husart->Init.WordLength value
2262 Set PCE and PS bits according to husart->Init.Parity value
2263 Set TE and RE bits according to husart->Init.Mode value
2264 Force OVER8 bit to 1 in order to reach the max USART frequencies */
2265 tmpreg
|= (uint32_t)husart
->Init
.WordLength
| husart
->Init
.Parity
| husart
->Init
.Mode
| USART_CR1_OVER8
;
2267 /* Write to USART CR1 */
2268 WRITE_REG(husart
->Instance
->CR1
, (uint32_t)tmpreg
);
2270 /*-------------------------- USART CR3 Configuration -----------------------*/
2271 /* Clear CTSE and RTSE bits */
2272 CLEAR_BIT(husart
->Instance
->CR3
, (USART_CR3_RTSE
| USART_CR3_CTSE
));
2274 /*-------------------------- USART BRR Configuration -----------------------*/
2276 if((husart
->Instance
== USART1
) || (husart
->Instance
== USART6
))
2278 husart
->Instance
->BRR
= USART_BRR(HAL_RCC_GetPCLK2Freq(), husart
->Init
.BaudRate
);
2281 if(husart
->Instance
== USART1
)
2283 husart
->Instance
->BRR
= USART_BRR(HAL_RCC_GetPCLK2Freq(), husart
->Init
.BaudRate
);
2288 husart
->Instance
->BRR
= USART_BRR(HAL_RCC_GetPCLK1Freq(), husart
->Init
.BaudRate
);
2296 #endif /* HAL_USART_MODULE_ENABLED */
2305 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/