before merging master
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Src / stm32f7xx_hal_usart.c
blob6af06ca1137a3639be005fa0dd8208b4816c404e
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_hal_usart.c
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
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
10 * Peripheral (USART).
11 * + Initialization and de-initialization functions
12 * + IO operation functions
13 * + Peripheral Control functions
15 @verbatim
16 ===============================================================================
17 ##### How to use this driver #####
18 ===============================================================================
19 [..]
20 The USART HAL driver can be used as follows:
22 (#) Declare a USART_HandleTypeDef handle structure.
23 (#) Initialize the USART low level resources by implement the HAL_USART_MspInit ()API:
24 (##) Enable the USARTx interface clock.
25 (##) USART pins configuration:
26 (+++) Enable the clock for the USART GPIOs.
27 (+++) Configure these USART pins as alternate function pull-up.
28 (##) NVIC configuration if you need to use interrupt process (HAL_USART_Transmit_IT(),
29 HAL_USART_Receive_IT() and HAL_USART_TransmitReceive_IT() APIs):
30 (+++) Configure the USARTx interrupt priority.
31 (+++) Enable the NVIC USART IRQ handle.
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_IT() and HAL_USART_TransmitReceive_IT() APIs):
37 (+++) Declare a DMA handle structure for the Tx/Rx stream.
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 Stream.
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 Stream.
44 (#) Program the Baud Rate, Word Length, Stop Bit, Parity, Hardware
45 flow control and Mode(Receiver/Transmitter) in the husart Init structure.
47 (#) Initialize the USART registers by calling the HAL_USART_Init() API:
48 (++) These API's configures also the low level Hardware (GPIO, CLOCK, CORTEX...etc)
49 by calling the customed HAL_USART_MspInit(&husart) API.
51 @endverbatim
52 ******************************************************************************
53 * @attention
55 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
57 * Redistribution and use in source and binary forms, with or without modification,
58 * are permitted provided that the following conditions are met:
59 * 1. Redistributions of source code must retain the above copyright notice,
60 * this list of conditions and the following disclaimer.
61 * 2. Redistributions in binary form must reproduce the above copyright notice,
62 * this list of conditions and the following disclaimer in the documentation
63 * and/or other materials provided with the distribution.
64 * 3. Neither the name of STMicroelectronics nor the names of its contributors
65 * may be used to endorse or promote products derived from this software
66 * without specific prior written permission.
68 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
69 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
70 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
71 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
72 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
73 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
74 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
75 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
76 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
77 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
79 ******************************************************************************
82 /* Includes ------------------------------------------------------------------*/
83 #include "stm32f7xx_hal.h"
85 /** @addtogroup STM32F7xx_HAL_Driver
86 * @{
89 /** @defgroup USART USART
90 * @brief HAL USART Synchronous module driver
91 * @{
94 #ifdef HAL_USART_MODULE_ENABLED
96 /* Private typedef -----------------------------------------------------------*/
97 /* Private define ------------------------------------------------------------*/
98 /** @addtogroup USART_Private_Constants
99 * @{
101 #define DUMMY_DATA ((uint16_t) 0xFFFFU)
102 #define TEACK_REACK_TIMEOUT ((uint32_t) 1000U)
103 #define USART_CR1_FIELDS ((uint32_t)(USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | \
104 USART_CR1_TE | USART_CR1_RE | USART_CR1_OVER8))
105 #define USART_CR2_FIELDS ((uint32_t)(USART_CR2_CPHA | USART_CR2_CPOL | \
106 USART_CR2_CLKEN | USART_CR2_LBCL | USART_CR2_STOP))
108 * @}
110 /* Private macro -------------------------------------------------------------*/
111 /* Private variables ---------------------------------------------------------*/
112 /* Private function prototypes -----------------------------------------------*/
113 /* Private functions ---------------------------------------------------------*/
114 /** @addtogroup USART_Private_Functions
115 * @{
117 static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma);
118 static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
119 static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma);
120 static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
121 static void USART_DMAError(DMA_HandleTypeDef *hdma);
122 static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma);
123 static void USART_EndTxTransfer(USART_HandleTypeDef *husart);
124 static void USART_EndRxTransfer(USART_HandleTypeDef *husart);
125 static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout);
126 static HAL_StatusTypeDef USART_SetConfig(USART_HandleTypeDef *husart);
127 static HAL_StatusTypeDef USART_CheckIdleState(USART_HandleTypeDef *husart);
128 static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart);
129 static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart);
130 static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart);
131 static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart);
134 * @}
137 /* Exported functions --------------------------------------------------------*/
139 /** @defgroup USART_Exported_Functions USART Exported Functions
140 * @{
143 /** @defgroup USART_Exported_Functions_Group1 USART Initialization and de-initialization functions
144 * @brief Initialization and Configuration functions
146 @verbatim
147 ===============================================================================
148 ##### Initialization and Configuration functions #####
149 ===============================================================================
150 [..]
151 This subsection provides a set of functions allowing to initialize the USART
152 in asynchronous and in synchronous modes.
153 (+) For the asynchronous mode only these parameters can be configured:
154 (++) Baud Rate
155 (++) Word Length
156 (++) Stop Bit
157 (++) Parity: If the parity is enabled, then the MSB bit of the data written
158 in the data register is transmitted but is changed by the parity bit.
159 (++) USART polarity
160 (++) USART phase
161 (++) USART LastBit
162 (++) Receiver/transmitter modes
164 [..]
165 The HAL_USART_Init() function follows the USART synchronous configuration
166 procedure (details for the procedure are available in reference manual).
168 @endverbatim
170 Depending on the frame length defined by the M1 and M0 bits (7-bit,
171 8-bit or 9-bit), the possible USART frame formats are as listed in the
172 following table:
174 +---------------------------------------------------------------+
175 | M1M0 bits | PCE bit | USART frame |
176 |-----------------------|---------------------------------------|
177 | 10 | 0 | | SB | 7-bit data | STB | |
178 |-----------|-----------|---------------------------------------|
179 | 10 | 1 | | SB | 6-bit data | PB | STB | |
180 +---------------------------------------------------------------+
182 * @{
186 * @brief Initializes the USART mode according to the specified
187 * parameters in the USART_InitTypeDef and create the associated handle.
188 * @param husart: USART handle
189 * @retval HAL status
191 HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart)
193 /* Check the USART handle allocation */
194 if(husart == NULL)
196 return HAL_ERROR;
199 /* Check the parameters */
200 assert_param(IS_USART_INSTANCE(husart->Instance));
202 if(husart->State == HAL_USART_STATE_RESET)
204 /* Allocate lock resource and initialize it */
205 husart->Lock = HAL_UNLOCKED;
206 /* Init the low level hardware : GPIO, CLOCK */
207 HAL_USART_MspInit(husart);
210 husart->State = HAL_USART_STATE_BUSY;
212 /* Disable the Peripheral */
213 __HAL_USART_DISABLE(husart);
215 /* Set the Usart Communication parameters */
216 if (USART_SetConfig(husart) == HAL_ERROR)
218 return HAL_ERROR;
221 /* In Synchronous mode, the following bits must be kept cleared:
222 - LINEN bit in the USART_CR2 register
223 - HDSEL, SCEN and IREN bits in the USART_CR3 register.*/
224 CLEAR_BIT(husart->Instance->CR2, USART_CR2_LINEN);
225 CLEAR_BIT(husart->Instance->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN));
227 /* Enable the Peripheral */
228 __HAL_USART_ENABLE(husart);
230 /* TEACK and/or REACK to check before moving husart->State to Ready */
231 return (USART_CheckIdleState(husart));
235 * @brief DeInitializes the USART peripheral
236 * @param husart: USART handle
237 * @retval HAL status
239 HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart)
241 /* Check the USART handle allocation */
242 if(husart == NULL)
244 return HAL_ERROR;
247 /* Check the parameters */
248 assert_param(IS_USART_INSTANCE(husart->Instance));
250 husart->State = HAL_USART_STATE_BUSY;
252 husart->Instance->CR1 = 0x0U;
253 husart->Instance->CR2 = 0x0U;
254 husart->Instance->CR3 = 0x0U;
256 /* DeInit the low level hardware */
257 HAL_USART_MspDeInit(husart);
259 husart->ErrorCode = HAL_USART_ERROR_NONE;
260 husart->State = HAL_USART_STATE_RESET;
262 /* Process Unlock */
263 __HAL_UNLOCK(husart);
265 return HAL_OK;
269 * @brief USART MSP Init
270 * @param husart: USART handle
271 * @retval None
273 __weak void HAL_USART_MspInit(USART_HandleTypeDef *husart)
275 /* Prevent unused argument(s) compilation warning */
276 UNUSED(husart);
278 /* NOTE : This function should not be modified, when the callback is needed,
279 the HAL_USART_MspInit can be implemented in the user file
284 * @brief USART MSP DeInit
285 * @param husart: USART handle
286 * @retval None
288 __weak void HAL_USART_MspDeInit(USART_HandleTypeDef *husart)
290 /* Prevent unused argument(s) compilation warning */
291 UNUSED(husart);
293 /* NOTE : This function should not be modified, when the callback is needed,
294 the HAL_USART_MspDeInit can be implemented in the user file
299 * @}
302 /** @defgroup USART_Exported_Functions_Group2 IO operation functions
303 * @brief USART Transmit and Receive functions
305 @verbatim
306 ===============================================================================
307 ##### IO operation functions #####
308 ===============================================================================
309 This subsection provides a set of functions allowing to manage the USART synchronous
310 data transfers.
312 [..] The USART supports master mode only: it cannot receive or send data related to an input
313 clock (SCLK is always an output).
315 (#) There are two mode of transfer:
316 (++) Blocking mode: The communication is performed in polling mode.
317 The HAL status of all data processing is returned by the same function
318 after finishing transfer.
319 (++) No-Blocking mode: The communication is performed using Interrupts
320 or DMA, These API's return the HAL status.
321 The end of the data processing will be indicated through the
322 dedicated USART IRQ when using Interrupt mode or the DMA IRQ when
323 using DMA mode.
324 The HAL_USART_TxCpltCallback(), HAL_USART_RxCpltCallback() and HAL_USART_TxRxCpltCallback() user callbacks
325 will be executed respectively at the end of the transmit or Receive process
326 The HAL_USART_ErrorCallback()user callback will be executed when a communication error is detected
328 (#) Blocking mode API's are :
329 (++) HAL_USART_Transmit()in simplex mode
330 (++) HAL_USART_Receive() in full duplex receive only
331 (++) HAL_USART_TransmitReceive() in full duplex mode
333 (#) Non-Blocking mode API's with Interrupt are :
334 (++) HAL_USART_Transmit_IT()in simplex mode
335 (++) HAL_USART_Receive_IT() in full duplex receive only
336 (++) HAL_USART_TransmitReceive_IT()in full duplex mode
337 (++) HAL_USART_IRQHandler()
339 (#) No-Blocking mode functions with DMA are :
340 (++) HAL_USART_Transmit_DMA()in simplex mode
341 (++) HAL_USART_Receive_DMA() in full duplex receive only
342 (++) HAL_USART_TransmitReceive_DMA() in full duplex mode
343 (++) HAL_USART_DMAPause()
344 (++) HAL_USART_DMAResume()
345 (++) HAL_USART_DMAStop()
347 (#) A set of Transfer Complete Callbacks are provided in No_Blocking mode:
348 (++) HAL_USART_TxCpltCallback()
349 (++) HAL_USART_RxCpltCallback()
350 (++) HAL_USART_TxHalfCpltCallback()
351 (++) HAL_USART_RxHalfCpltCallback()
352 (++) HAL_USART_ErrorCallback()
353 (++) HAL_USART_TxRxCpltCallback()
355 @endverbatim
356 * @{
360 * @brief Simplex Send an amount of data in blocking mode
361 * @param husart: USART handle
362 * @param pTxData: pointer to data buffer
363 * @param Size: amount of data to be sent
364 * @param Timeout : Timeout duration
365 * @retval HAL status
367 HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout)
369 uint16_t* tmp;
370 uint32_t tickstart = 0U;
372 if(husart->State == HAL_USART_STATE_READY)
374 if((pTxData == NULL) || (Size == 0U))
376 return HAL_ERROR;
379 /* Process Locked */
380 __HAL_LOCK(husart);
382 husart->ErrorCode = HAL_USART_ERROR_NONE;
383 husart->State = HAL_USART_STATE_BUSY_TX;
385 /* Init tickstart for timeout managment*/
386 tickstart = HAL_GetTick();
388 husart->TxXferSize = Size;
389 husart->TxXferCount = Size;
391 /* Check the remaining data to be sent */
392 while(husart->TxXferCount > 0U)
394 husart->TxXferCount--;
395 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
397 return HAL_TIMEOUT;
399 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
401 tmp = (uint16_t*) pTxData;
402 husart->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
403 pTxData += 2;
405 else
407 husart->Instance->TDR = (*pTxData++ & (uint8_t)0xFFU);
411 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
413 return HAL_TIMEOUT;
416 husart->State = HAL_USART_STATE_READY;
418 /* Process Unlocked */
419 __HAL_UNLOCK(husart);
421 return HAL_OK;
423 else
425 return HAL_BUSY;
430 * @brief Receive an amount of data in blocking mode
431 * @note To receive synchronous data, dummy data are simultaneously transmitted
432 * @param husart: USART handle
433 * @param pRxData: pointer to data buffer
434 * @param Size: amount of data to be received
435 * @param Timeout : Timeout duration
436 * @retval HAL status
438 HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
440 uint16_t* tmp;
441 uint16_t uhMask;
442 uint32_t tickstart = 0U;
444 if(husart->State == HAL_USART_STATE_READY)
446 if((pRxData == NULL) || (Size == 0U))
448 return HAL_ERROR;
450 /* Process Locked */
451 __HAL_LOCK(husart);
453 husart->ErrorCode = HAL_USART_ERROR_NONE;
454 husart->State = HAL_USART_STATE_BUSY_RX;
456 /* Init tickstart for timeout managment*/
457 tickstart = HAL_GetTick();
459 husart->RxXferSize = Size;
460 husart->RxXferCount = Size;
462 /* Computation of USART mask to apply to RDR register */
463 __HAL_USART_MASK_COMPUTATION(husart);
464 uhMask = husart->Mask;
466 /* as long as data have to be received */
467 while(husart->RxXferCount > 0U)
469 husart->RxXferCount--;
471 /* Wait until TC flag is set to send dummy byte in order to generate the
472 * clock for the slave to send data.
473 * Whatever the frame length (7, 8 or 9-bit long), the same dummy value
474 * can be written for all the cases. */
475 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
477 return HAL_TIMEOUT;
479 husart->Instance->TDR = (DUMMY_DATA & (uint16_t)0x0FFU);
481 /* Wait for RXNE Flag */
482 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
484 return HAL_TIMEOUT;
487 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
489 tmp = (uint16_t*) pRxData ;
490 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
491 pRxData +=2;
493 else
495 *pRxData++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
499 husart->State = HAL_USART_STATE_READY;
501 /* Process Unlocked */
502 __HAL_UNLOCK(husart);
504 return HAL_OK;
506 else
508 return HAL_BUSY;
513 * @brief Full-Duplex Send and Receive an amount of data in blocking mode
514 * @param husart: USART handle
515 * @param pTxData: pointer to TX data buffer
516 * @param pRxData: pointer to RX data buffer
517 * @param Size: amount of data to be sent (same amount to be received)
518 * @param Timeout : Timeout duration
519 * @retval HAL status
521 HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, uint32_t Timeout)
523 uint16_t* tmp;
524 uint16_t uhMask;
525 uint32_t tickstart = 0U;
527 if(husart->State == HAL_USART_STATE_READY)
529 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
531 return HAL_ERROR;
533 /* Process Locked */
534 __HAL_LOCK(husart);
536 husart->ErrorCode = HAL_USART_ERROR_NONE;
537 husart->State = HAL_USART_STATE_BUSY_RX;
539 /* Init tickstart for timeout managment*/
540 tickstart = HAL_GetTick();
542 husart->RxXferSize = Size;
543 husart->TxXferSize = Size;
544 husart->TxXferCount = Size;
545 husart->RxXferCount = Size;
547 /* Computation of USART mask to apply to RDR register */
548 __HAL_USART_MASK_COMPUTATION(husart);
549 uhMask = husart->Mask;
551 /* Check the remain data to be sent */
552 while(husart->TxXferCount > 0)
554 husart->TxXferCount--;
555 husart->RxXferCount--;
557 /* Wait until TC flag is set to send data */
558 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_TC, RESET, tickstart, Timeout) != HAL_OK)
560 return HAL_TIMEOUT;
562 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
564 tmp = (uint16_t*) pTxData;
565 husart->Instance->TDR = (*tmp & uhMask);
566 pTxData += 2;
568 else
570 husart->Instance->TDR = (*pTxData++ & (uint8_t)uhMask);
573 /* Wait for RXNE Flag */
574 if(USART_WaitOnFlagUntilTimeout(husart, USART_FLAG_RXNE, RESET, tickstart, Timeout) != HAL_OK)
576 return HAL_TIMEOUT;
579 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
581 tmp = (uint16_t*) pRxData ;
582 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
583 pRxData +=2U;
585 else
587 *pRxData++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
591 husart->State = HAL_USART_STATE_READY;
593 /* Process Unlocked */
594 __HAL_UNLOCK(husart);
596 return HAL_OK;
598 else
600 return HAL_BUSY;
605 * @brief Send an amount of data in interrupt mode
606 * @param husart: USART handle
607 * @param pTxData: pointer to data buffer
608 * @param Size: amount of data to be sent
609 * @retval HAL status
611 HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size)
613 if(husart->State == HAL_USART_STATE_READY)
615 if((pTxData == NULL ) || (Size == 0U))
617 return HAL_ERROR;
620 /* Process Locked */
621 __HAL_LOCK(husart);
623 husart->pTxBuffPtr = pTxData;
624 husart->TxXferSize = Size;
625 husart->TxXferCount = Size;
627 husart->ErrorCode = HAL_USART_ERROR_NONE;
628 husart->State = HAL_USART_STATE_BUSY_TX;
630 /* The USART Error Interrupts: (Frame error, noise error, overrun error)
631 are not managed by the USART Transmit Process to avoid the overrun interrupt
632 when the usart mode is configured for transmit and receive "USART_MODE_TX_RX"
633 to benefit for the frame error and noise interrupts the usart mode should be
634 configured only for transmit "USART_MODE_TX" */
636 /* Process Unlocked */
637 __HAL_UNLOCK(husart);
639 /* Enable the USART Transmit Data Register Empty Interrupt */
640 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
642 return HAL_OK;
644 else
646 return HAL_BUSY;
651 * @brief Receive an amount of data in blocking mode
652 * To receive synchronous data, dummy data are simultaneously transmitted
653 * @param husart: USART handle
654 * @param pRxData: pointer to data buffer
655 * @param Size: amount of data to be received
656 * @retval HAL status
658 HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size)
660 if(husart->State == HAL_USART_STATE_READY)
662 if((pRxData == NULL ) || (Size == 0U))
664 return HAL_ERROR;
666 /* Process Locked */
667 __HAL_LOCK(husart);
669 husart->pRxBuffPtr = pRxData;
670 husart->RxXferSize = Size;
671 husart->RxXferCount = Size;
673 __HAL_USART_MASK_COMPUTATION(husart);
675 husart->ErrorCode = HAL_USART_ERROR_NONE;
676 husart->State = HAL_USART_STATE_BUSY_RX;
678 /* Enable the USART Parity Error and Data Register not empty Interrupts */
679 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE | USART_CR1_RXNEIE);
681 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
682 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
684 /* Process Unlocked */
685 __HAL_UNLOCK(husart);
688 /* Send dummy byte in order to generate the clock for the Slave to send the next data */
689 if(husart->Init.WordLength == USART_WORDLENGTH_9B)
691 husart->Instance->TDR = (DUMMY_DATA & (uint16_t)0x01FFU);
693 else
695 husart->Instance->TDR = (DUMMY_DATA & (uint16_t)0x00FFU);
698 return HAL_OK;
700 else
702 return HAL_BUSY;
707 * @brief Full-Duplex Send and Receive an amount of data in interrupt mode
708 * @param husart: USART handle
709 * @param pTxData: pointer to TX data buffer
710 * @param pRxData: pointer to RX data buffer
711 * @param Size: amount of data to be sent (same amount to be received)
712 * @retval HAL status
714 HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
717 if(husart->State == HAL_USART_STATE_READY)
719 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
721 return HAL_ERROR;
723 /* Process Locked */
724 __HAL_LOCK(husart);
726 husart->pRxBuffPtr = pRxData;
727 husart->RxXferSize = Size;
728 husart->RxXferCount = Size;
729 husart->pTxBuffPtr = pTxData;
730 husart->TxXferSize = Size;
731 husart->TxXferCount = Size;
733 /* Computation of USART mask to apply to RDR register */
734 __HAL_USART_MASK_COMPUTATION(husart);
736 husart->ErrorCode = HAL_USART_ERROR_NONE;
737 husart->State = HAL_USART_STATE_BUSY_TX_RX;
739 /* Enable the USART Data Register not empty Interrupt */
740 SET_BIT(husart->Instance->CR1, USART_CR1_RXNEIE);
742 /* Enable the USART Parity Error Interrupt */
743 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
745 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
746 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
748 /* Process Unlocked */
749 __HAL_UNLOCK(husart);
751 /* Enable the USART Transmit Data Register Empty Interrupt */
752 __HAL_USART_ENABLE_IT(husart, USART_IT_TXE);
754 return HAL_OK;
756 else
758 return HAL_BUSY;
763 * @brief Send an amount of data in DMA mode
764 * @param husart: USART handle
765 * @param pTxData: pointer to data buffer
766 * @param Size: amount of data to be sent
767 * @retval HAL status
769 HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size)
771 uint32_t *tmp;
773 if(husart->State == HAL_USART_STATE_READY)
775 if((pTxData == NULL ) || (Size == 0U))
777 return HAL_ERROR;
779 /* Process Locked */
780 __HAL_LOCK(husart);
782 husart->pTxBuffPtr = pTxData;
783 husart->TxXferSize = Size;
784 husart->TxXferCount = Size;
786 husart->ErrorCode = HAL_USART_ERROR_NONE;
787 husart->State = HAL_USART_STATE_BUSY_TX;
789 /* Set the USART DMA transfer complete callback */
790 husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt;
792 /* Set the USART DMA Half transfer complete callback */
793 husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt;
795 /* Set the DMA error callback */
796 husart->hdmatx->XferErrorCallback = USART_DMAError;
798 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
799 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
800 SET_BIT(husart->Instance->ISR, (USART_ISR_PE | USART_ISR_FE | USART_ISR_NE | USART_ISR_ORE));
802 /* Enable the USART transmit DMA channel */
803 tmp = (uint32_t*)&pTxData;
804 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
806 /* Clear the TC flag in the SR register by writing 0 to it */
807 __HAL_USART_CLEAR_IT(husart, USART_FLAG_TC);
809 /* Process Unlocked */
810 __HAL_UNLOCK(husart);
812 /* Enable the DMA transfer for transmit request by setting the DMAT bit
813 in the USART CR3 register */
814 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
816 return HAL_OK;
818 else
820 return HAL_BUSY;
825 * @brief Receive an amount of data in DMA mode
826 * @param husart: USART handle
827 * @param pRxData: pointer to data buffer
828 * @param Size: amount of data to be received
829 * @note When the USART parity is enabled (PCE = 1), the received data contain
830 * the parity bit (MSB position)
831 * @retval HAL status
832 * @note The USART DMA transmit stream must be configured in order to generate the clock for the slave.
834 HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size)
836 uint32_t *tmp;
838 if(husart->State == HAL_USART_STATE_READY)
840 if((pRxData == NULL ) || (Size == 0U))
842 return HAL_ERROR;
845 /* Process Locked */
846 __HAL_LOCK(husart);
848 husart->pRxBuffPtr = pRxData;
849 husart->RxXferSize = Size;
850 husart->pTxBuffPtr = pRxData;
851 husart->TxXferSize = Size;
853 husart->ErrorCode = HAL_USART_ERROR_NONE;
854 husart->State = HAL_USART_STATE_BUSY_RX;
856 /* Set the USART DMA Rx transfer complete callback */
857 husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt;
859 /* Set the USART DMA Half transfer complete callback */
860 husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt;
862 /* Set the USART DMA Rx transfer error callback */
863 husart->hdmarx->XferErrorCallback = USART_DMAError;
865 /* Set the DMA abort callback */
866 husart->hdmatx->XferAbortCallback = NULL;
868 /* Set the USART Tx DMA transfer complete callback as NULL because the communication closing
869 is performed in DMA reception complete callback */
870 husart->hdmatx->XferHalfCpltCallback = NULL;
871 husart->hdmatx->XferCpltCallback = NULL;
873 /* Set the DMA error callback */
874 husart->hdmatx->XferErrorCallback = USART_DMAError;
876 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
877 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
878 SET_BIT(husart->Instance->ISR, (USART_ISR_PE | USART_ISR_FE | USART_ISR_NE | USART_ISR_ORE));
880 /* Enable the USART receive DMA channel */
881 tmp = (uint32_t*)&pRxData;
882 HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->RDR, *(uint32_t*)tmp, Size);
884 /* Enable the USART transmit DMA channel: the transmit stream is used in order
885 to generate in the non-blocking mode the clock to the slave device,
886 this mode isn't a simplex receive mode but a full-duplex receive mode */
887 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
889 /* Process Unlocked */
890 __HAL_UNLOCK(husart);
892 /* Enable the USART Parity Error Interrupt */
893 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
895 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
896 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
898 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
899 in the USART CR3 register */
900 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
902 /* Enable the DMA transfer for transmit request by setting the DMAT bit
903 in the USART CR3 register */
904 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
907 return HAL_OK;
909 else
911 return HAL_BUSY;
916 * @brief Full-Duplex Transmit Receive an amount of data in non blocking mode
917 * @param husart: USART handle
918 * @param pTxData: pointer to TX data buffer
919 * @param pRxData: pointer to RX data buffer
920 * @param Size: amount of data to be received/sent
921 * @note When the USART parity is enabled (PCE = 1) the data received contain the parity bit.
922 * @retval HAL status
924 HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size)
926 uint32_t *tmp;
928 if(husart->State == HAL_USART_STATE_READY)
930 if((pTxData == NULL) || (pRxData == NULL) || (Size == 0U))
932 return HAL_ERROR;
934 /* Process Locked */
935 __HAL_LOCK(husart);
937 husart->pRxBuffPtr = pRxData;
938 husart->RxXferSize = Size;
939 husart->pTxBuffPtr = pTxData;
940 husart->TxXferSize = Size;
942 husart->ErrorCode = HAL_USART_ERROR_NONE;
943 husart->State = HAL_USART_STATE_BUSY_TX_RX;
945 /* Set the USART DMA Rx transfer complete callback */
946 husart->hdmarx->XferCpltCallback = USART_DMAReceiveCplt;
948 /* Set the USART DMA Half transfer complete callback */
949 husart->hdmarx->XferHalfCpltCallback = USART_DMARxHalfCplt;
951 /* Set the USART DMA Tx transfer complete callback */
952 husart->hdmatx->XferCpltCallback = USART_DMATransmitCplt;
954 /* Set the USART DMA Half transfer complete callback */
955 husart->hdmatx->XferHalfCpltCallback = USART_DMATxHalfCplt;
957 /* Set the USART DMA Tx transfer error callback */
958 husart->hdmatx->XferErrorCallback = USART_DMAError;
960 /* Set the USART DMA Rx transfer error callback */
961 husart->hdmarx->XferErrorCallback = USART_DMAError;
963 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
964 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
965 SET_BIT(husart->Instance->ISR, (USART_ISR_PE | USART_ISR_FE | USART_ISR_NE | USART_ISR_ORE));
967 /* Enable the USART receive DMA channel */
968 tmp = (uint32_t*)&pRxData;
969 HAL_DMA_Start_IT(husart->hdmarx, (uint32_t)&husart->Instance->RDR, *(uint32_t*)tmp, Size);
971 /* Enable the USART transmit DMA channel */
972 tmp = (uint32_t*)&pTxData;
973 HAL_DMA_Start_IT(husart->hdmatx, *(uint32_t*)tmp, (uint32_t)&husart->Instance->TDR, Size);
975 /* Clear the TC flag in the SR register by writing 0 to it */
976 __HAL_USART_CLEAR_IT(husart, USART_FLAG_TC);
978 /* Process Unlocked */
979 __HAL_UNLOCK(husart);
981 /* Enable the USART Parity Error Interrupt */
982 SET_BIT(husart->Instance->CR1, USART_CR1_PEIE);
984 /* Enable the USART Error Interrupt: (Frame error, noise error, overrun error) */
985 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
987 /* Enable the DMA transfer for the receiver request by setting the DMAR bit
988 in the USART CR3 register */
989 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
991 /* Enable the DMA transfer for transmit request by setting the DMAT bit
992 in the USART CR3 register */
993 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
995 return HAL_OK;
997 else
999 return HAL_BUSY;
1004 * @brief Pauses the DMA Transfer.
1005 * @param husart: USART handle
1006 * @retval None
1008 HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart)
1010 /* Process Locked */
1011 __HAL_LOCK(husart);
1013 if(husart->State == HAL_USART_STATE_BUSY_TX)
1015 /* Disable the USART DMA Tx request */
1016 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1018 else if(husart->State == HAL_USART_STATE_BUSY_RX)
1020 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1021 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1022 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1023 /* Disable the USART DMA Rx request */
1024 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1026 else if(husart->State == HAL_USART_STATE_BUSY_TX_RX)
1028 /* Disable the USART DMA Tx request */
1029 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1030 /* Disable the USART DMA Rx request */
1031 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1034 /* Process Unlocked */
1035 __HAL_UNLOCK(husart);
1037 return HAL_OK;
1041 * @brief Resumes the DMA Transfer.
1042 * @param husart: USART handle
1043 * @retval None
1045 HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart)
1047 /* Process Locked */
1048 __HAL_LOCK(husart);
1050 if(husart->State == HAL_USART_STATE_BUSY_TX)
1052 /* Enable the USART DMA Tx request */
1053 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1055 else if(husart->State == HAL_USART_STATE_BUSY_RX)
1057 /* Clear the Overrun flag before resuming the Rx transfer*/
1058 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_OREF);
1060 /* Reenable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1061 SET_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1062 SET_BIT(husart->Instance->CR3, USART_CR3_EIE);
1064 /* Enable the USART DMA Rx request */
1065 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1067 else if(husart->State == HAL_USART_STATE_BUSY_TX_RX)
1069 /* Clear the Overrun flag before resuming the Rx transfer*/
1070 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_OREF);
1072 /* Enable the USART DMA Rx request before the DMA Tx request */
1073 SET_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1075 /* Enable the USART DMA Tx request */
1076 SET_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1079 /* Process Unlocked */
1080 __HAL_UNLOCK(husart);
1082 return HAL_OK;
1086 * @brief Stops the DMA Transfer.
1087 * @param husart: USART handle
1088 * @retval None
1090 HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart)
1092 /* The Lock is not implemented on this API to allow the user application
1093 to call the HAL USART API under callbacks HAL_USART_TxCpltCallback() / HAL_USART_RxCpltCallback() /
1094 HAL_USART_TxHalfCpltCallback / HAL_USART_RxHalfCpltCallback:
1095 indeed, when HAL_DMA_Abort() API is called, the DMA TX/RX Transfer or Half Transfer complete
1096 interrupt is generated if the DMA transfer interruption occurs at the middle or at the end of
1097 the stream and the corresponding call back is executed. */
1099 /* Stop USART DMA Tx request if ongoing */
1100 if ((husart->State == HAL_USART_STATE_BUSY_TX) &&
1101 (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)))
1103 USART_EndTxTransfer(husart);
1105 /* Abort the USART DMA Tx channel */
1106 if(husart->hdmatx != NULL)
1108 HAL_DMA_Abort(husart->hdmatx);
1111 /* Disable the USART Tx DMA request */
1112 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1115 /* Stop USART DMA Rx request if ongoing */
1116 if ((husart->State == HAL_USART_STATE_BUSY_RX) &&
1117 (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)))
1119 USART_EndRxTransfer(husart);
1121 /* Abort the USART DMA Rx channel */
1122 if(husart->hdmarx != NULL)
1124 HAL_DMA_Abort(husart->hdmarx);
1127 /* Disable the USART Rx DMA request */
1128 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1131 return HAL_OK;
1135 * @brief This function handles USART interrupt request.
1136 * @param husart: USART handle
1137 * @retval None
1139 void HAL_USART_IRQHandler(USART_HandleTypeDef *husart)
1141 uint32_t isrflags = READ_REG(husart->Instance->ISR);
1142 uint32_t cr1its = READ_REG(husart->Instance->CR1);
1143 uint32_t cr3its = READ_REG(husart->Instance->CR3);
1144 uint32_t errorflags;
1146 /* If no error occurs */
1147 errorflags = (isrflags & (uint32_t)(USART_ISR_PE | USART_ISR_FE | USART_ISR_ORE | USART_ISR_NE));
1148 if (errorflags == RESET)
1150 /* USART in mode Receiver --------------------------------------------------*/
1151 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1153 if(husart->State == HAL_USART_STATE_BUSY_RX)
1155 USART_Receive_IT(husart);
1157 else
1159 USART_TransmitReceive_IT(husart);
1164 /* If some errors occur */
1165 if( (errorflags != RESET)
1166 && ( ((cr3its & USART_CR3_EIE) != RESET)
1167 || ((cr1its & (USART_CR1_RXNEIE | USART_CR1_PEIE)) != RESET)) )
1170 /* USART parity error interrupt occurred ------------------------------------*/
1171 if(((isrflags & USART_ISR_PE) != RESET) && ((cr1its & USART_CR1_PEIE) != RESET))
1173 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_PEF);
1174 husart->ErrorCode |= HAL_USART_ERROR_PE;
1177 /* USART frame error interrupt occurred -------------------------------------*/
1178 if(((isrflags & USART_ISR_FE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1180 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_FEF);
1181 husart->ErrorCode |= HAL_USART_ERROR_FE;
1184 /* USART noise error interrupt occurred -------------------------------------*/
1185 if(((isrflags & USART_ISR_NE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1187 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_NEF);
1188 husart->ErrorCode |= HAL_USART_ERROR_NE;
1191 /* USART Over-Run interrupt occurred ----------------------------------------*/
1192 if(((isrflags & USART_ISR_ORE) != RESET) && ((cr3its & USART_CR3_EIE) != RESET))
1194 __HAL_USART_CLEAR_IT(husart, USART_CLEAR_OREF);
1195 husart->ErrorCode |= HAL_USART_ERROR_ORE;
1198 /* Call USART Error Call back function if need be --------------------------*/
1199 if(husart->ErrorCode != HAL_USART_ERROR_NONE)
1201 /* USART in mode Receiver ---------------------------------------------------*/
1202 if(((isrflags & USART_ISR_RXNE) != RESET) && ((cr1its & USART_CR1_RXNEIE) != RESET))
1204 USART_Receive_IT(husart);
1207 /* If Overrun error occurs, or if any error occurs in DMA mode reception,
1208 consider error as blocking */
1209 if (((husart->ErrorCode & HAL_USART_ERROR_ORE) != RESET) ||
1210 (HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)))
1212 /* Blocking error : transfer is aborted
1213 Set the USART state ready to be able to start again the process,
1214 Disable Rx Interrupts, and disable Rx DMA request, if ongoing */
1215 USART_EndRxTransfer(husart);
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 */
1223 if(husart->hdmarx != NULL)
1225 /* Set the USART DMA Abort callback :
1226 will lead to call HAL_USART_ErrorCallback() at end of DMA abort procedure */
1227 husart->hdmarx->XferAbortCallback = USART_DMAAbortOnError;
1229 /* Abort DMA RX */
1230 if(HAL_DMA_Abort_IT(husart->hdmarx) != HAL_OK)
1232 /* Call Directly husart->hdmarx->XferAbortCallback function in case of error */
1233 husart->hdmarx->XferAbortCallback(husart->hdmarx);
1236 else
1238 /* Call user error callback */
1239 HAL_USART_ErrorCallback(husart);
1242 else
1244 /* Call user error callback */
1245 HAL_USART_ErrorCallback(husart);
1248 else
1250 /* Non Blocking error : transfer could go on.
1251 Error is notified to user through user error callback */
1252 HAL_USART_ErrorCallback(husart);
1253 husart->ErrorCode = HAL_USART_ERROR_NONE;
1256 return;
1258 } /* End if some error occurs */
1260 /* USART in mode Transmitter -----------------------------------------------*/
1261 if(((isrflags & USART_ISR_TXE) != RESET) && ((cr1its & USART_CR1_TXEIE) != RESET))
1263 if(husart->State == HAL_USART_STATE_BUSY_TX)
1265 USART_Transmit_IT(husart);
1267 else
1269 USART_TransmitReceive_IT(husart);
1271 return;
1274 /* USART in mode Transmitter (transmission end) -----------------------------*/
1275 if(((isrflags & USART_ISR_TC) != RESET) && ((cr1its & USART_CR1_TCIE) != RESET))
1277 USART_EndTransmit_IT(husart);
1278 return;
1283 * @brief Tx Transfer completed callbacks
1284 * @param husart: USART handle
1285 * @retval None
1287 __weak void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart)
1289 /* Prevent unused argument(s) compilation warning */
1290 UNUSED(husart);
1292 /* NOTE : This function should not be modified, when the callback is needed,
1293 the HAL_USART_TxCpltCallback can be implemented in the user file
1298 * @brief Tx Half Transfer completed callbacks.
1299 * @param husart: USART handle
1300 * @retval None
1302 __weak void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart)
1304 /* Prevent unused argument(s) compilation warning */
1305 UNUSED(husart);
1307 /* NOTE: This function should not be modified, when the callback is needed,
1308 the HAL_USART_TxHalfCpltCallback can be implemented in the user file
1313 * @brief Rx Transfer completed callbacks.
1314 * @param husart: USART handle
1315 * @retval None
1317 __weak void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart)
1319 /* Prevent unused argument(s) compilation warning */
1320 UNUSED(husart);
1322 /* NOTE: This function should not be modified, when the callback is needed,
1323 the HAL_USART_RxCpltCallback can be implemented in the user file
1328 * @brief Rx Half Transfer completed callbacks
1329 * @param husart: usart handle
1330 * @retval None
1332 __weak void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart)
1334 /* Prevent unused argument(s) compilation warning */
1335 UNUSED(husart);
1337 /* NOTE : This function should not be modified, when the callback is needed,
1338 the HAL_USART_RxHalfCpltCallback can be implemented in the user file
1343 * @brief Tx/Rx Transfers completed callback for the non-blocking process
1344 * @param husart: USART handle
1345 * @retval None
1347 __weak void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart)
1349 /* Prevent unused argument(s) compilation warning */
1350 UNUSED(husart);
1352 /* NOTE : This function should not be modified, when the callback is needed,
1353 the HAL_USART_TxRxCpltCallback can be implemented in the user file
1358 * @brief USART error callbacks
1359 * @param husart: USART handle
1360 * @retval None
1362 __weak void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart)
1364 /* Prevent unused argument(s) compilation warning */
1365 UNUSED(husart);
1367 /* NOTE : This function should not be modified, when the callback is needed,
1368 the HAL_USART_ErrorCallback can be implemented in the user file
1373 * @}
1376 /** @defgroup USART_Exported_Functions_Group3 Peripheral State and Errors functions
1377 * @brief USART State and Errors functions
1379 @verbatim
1380 ==============================================================================
1381 ##### Peripheral State and Errors functions #####
1382 ==============================================================================
1383 [..]
1384 This subsection provides a set of functions allowing to return the State of
1385 USART communication
1386 process, return Peripheral Errors occurred during communication process
1387 (+) HAL_USART_GetState() API can be helpful to check in run-time the state
1388 of the USART peripheral.
1389 (+) HAL_USART_GetError() check in run-time errors that could be occurred during
1390 communication.
1391 @endverbatim
1392 * @{
1396 * @brief return the USART state
1397 * @param husart: USART handle
1398 * @retval HAL state
1400 HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart)
1402 return husart->State;
1406 * @brief Return the USART error code
1407 * @param husart : pointer to a USART_HandleTypeDef structure that contains
1408 * the configuration information for the specified USART.
1409 * @retval USART Error Code
1411 uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart)
1413 return husart->ErrorCode;
1417 * @}
1422 * @brief Simplex Send an amount of data in non-blocking mode.
1423 * @note Function called under interruption only, once
1424 * interruptions have been enabled by HAL_USART_Transmit_IT().
1425 * @param husart: USART handle
1426 * @retval HAL status
1427 * @note The USART errors are not managed to avoid the overrun error.
1429 static HAL_StatusTypeDef USART_Transmit_IT(USART_HandleTypeDef *husart)
1431 uint16_t* tmp;
1433 if(husart->State == HAL_USART_STATE_BUSY_TX)
1436 if(husart->TxXferCount == 0U)
1438 /* Disable the USART Transmit data register empty interrupt */
1439 __HAL_USART_DISABLE_IT(husart, USART_IT_TXE);
1441 /* Enable the USART Transmit Complete Interrupt */
1442 __HAL_USART_ENABLE_IT(husart, USART_IT_TC);
1444 return HAL_OK;
1446 else
1448 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
1450 tmp = (uint16_t*) husart->pTxBuffPtr;
1451 husart->Instance->TDR = (*tmp & (uint16_t)0x01FFU);
1452 husart->pTxBuffPtr += 2U;
1454 else
1456 husart->Instance->TDR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)0xFF);
1459 husart->TxXferCount--;
1461 return HAL_OK;
1464 else
1466 return HAL_BUSY;
1471 * @brief Wraps up transmission in non-blocking mode.
1472 * @param husart: pointer to a USART_HandleTypeDef structure that contains
1473 * the configuration information for the specified USART module.
1474 * @retval HAL status
1476 static HAL_StatusTypeDef USART_EndTransmit_IT(USART_HandleTypeDef *husart)
1478 /* Disable the USART Transmit Complete Interrupt */
1479 CLEAR_BIT(husart->Instance->CR1, USART_CR1_TCIE);
1481 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1482 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1484 husart->State = HAL_USART_STATE_READY;
1486 HAL_USART_TxCpltCallback(husart);
1488 return HAL_OK;
1492 * @brief Simplex Receive an amount of data in non-blocking mode.
1493 * Function called under interruption only, once
1494 * interruptions have been enabled by HAL_USART_Receive_IT()
1495 * @param husart: USART handle
1496 * @retval HAL status
1498 static HAL_StatusTypeDef USART_Receive_IT(USART_HandleTypeDef *husart)
1500 uint16_t* tmp;
1501 uint16_t uhMask = husart->Mask;
1503 if(husart->State == HAL_USART_STATE_BUSY_RX)
1506 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
1508 tmp = (uint16_t*) husart->pRxBuffPtr;
1509 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
1510 husart->pRxBuffPtr += 2U;
1512 else
1514 *husart->pRxBuffPtr++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
1516 /* Send dummy byte in order to generate the clock for the Slave to Send the next data */
1517 husart->Instance->TDR = (DUMMY_DATA & (uint16_t)0x00FFU);
1519 if(--husart->RxXferCount == 0U)
1521 CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE);
1523 /* Disable the USART Parity Error Interrupt */
1524 CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1526 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1527 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1529 husart->State = HAL_USART_STATE_READY;
1531 HAL_USART_RxCpltCallback(husart);
1533 return HAL_OK;
1536 return HAL_OK;
1538 else
1540 return HAL_BUSY;
1545 * @brief Full-Duplex Send receive an amount of data in full-duplex mode (non-blocking).
1546 * Function called under interruption only, once
1547 * interruptions have been enabled by HAL_USART_TransmitReceive_IT()
1548 * @param husart: USART handle
1549 * @retval HAL status
1551 static HAL_StatusTypeDef USART_TransmitReceive_IT(USART_HandleTypeDef *husart)
1553 uint16_t* tmp;
1554 uint16_t uhMask = husart->Mask;
1556 if(husart->State == HAL_USART_STATE_BUSY_TX_RX)
1558 if(husart->TxXferCount != 0x00U)
1560 if(__HAL_USART_GET_FLAG(husart, USART_FLAG_TXE) != RESET)
1562 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
1564 tmp = (uint16_t*) husart->pTxBuffPtr;
1565 husart->Instance->TDR = (uint16_t)(*tmp & uhMask);
1566 husart->pTxBuffPtr += 2U;
1568 else
1570 husart->Instance->TDR = (uint8_t)(*husart->pTxBuffPtr++ & (uint8_t)uhMask);
1572 husart->TxXferCount--;
1574 /* Check the latest data transmitted */
1575 if(husart->TxXferCount == 0U)
1577 CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE);
1582 if(husart->RxXferCount != 0x00U)
1584 if(__HAL_USART_GET_FLAG(husart, USART_FLAG_RXNE) != RESET)
1586 if((husart->Init.WordLength == USART_WORDLENGTH_9B) && (husart->Init.Parity == USART_PARITY_NONE))
1588 tmp = (uint16_t*) husart->pRxBuffPtr;
1589 *tmp = (uint16_t)(husart->Instance->RDR & uhMask);
1590 husart->pRxBuffPtr += 2U;
1592 else
1594 *husart->pRxBuffPtr++ = (uint8_t)(husart->Instance->RDR & (uint8_t)uhMask);
1596 husart->RxXferCount--;
1600 /* Check the latest data received */
1601 if(husart->RxXferCount == 0U)
1603 CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE);
1605 /* Disable the USART Parity Error Interrupt */
1606 CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1608 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1609 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1611 husart->State = HAL_USART_STATE_READY;
1613 HAL_USART_TxRxCpltCallback(husart);
1615 return HAL_OK;
1618 return HAL_OK;
1620 else
1622 return HAL_BUSY;
1627 * @brief This function handles USART Communication Timeout.
1628 * @param husart USART handle
1629 * @param Flag specifies the USART flag to check.
1630 * @param Status The new Flag status (SET or RESET).
1631 * @param Tickstart Tick start value
1632 * @param Timeout Timeout duration
1633 * @retval HAL status
1635 static HAL_StatusTypeDef USART_WaitOnFlagUntilTimeout(USART_HandleTypeDef *husart, uint32_t Flag, FlagStatus Status, uint32_t Tickstart, uint32_t Timeout)
1637 /* Wait until flag is set */
1638 while((__HAL_USART_GET_FLAG(husart, Flag) ? SET : RESET) == Status)
1640 /* Check for the Timeout */
1641 if(Timeout != HAL_MAX_DELAY)
1643 if((Timeout == 0U)||((HAL_GetTick()-Tickstart) >= Timeout))
1645 /* Disable the USART Transmit Complete Interrupt */
1646 CLEAR_BIT(husart->Instance->CR1, USART_CR1_TXEIE);
1648 /* Disable the USART RXNE Interrupt */
1649 CLEAR_BIT(husart->Instance->CR1, USART_CR1_RXNEIE);
1651 /* Disable the USART Parity Error Interrupt */
1652 CLEAR_BIT(husart->Instance->CR1, USART_CR1_PEIE);
1654 /* Disable the USART Error Interrupt: (Frame error, noise error, overrun error) */
1655 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1657 husart->State= HAL_USART_STATE_READY;
1659 /* Process Unlocked */
1660 __HAL_UNLOCK(husart);
1662 return HAL_TIMEOUT;
1666 return HAL_OK;
1671 * @brief DMA USART transmit process complete callback
1672 * @param hdma: DMA handle
1673 * @retval None
1675 static void USART_DMATransmitCplt(DMA_HandleTypeDef *hdma)
1677 USART_HandleTypeDef* husart = ( USART_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1679 /* DMA Normal mode */
1680 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U)
1682 husart->TxXferCount = 0U;
1684 if(husart->State == HAL_USART_STATE_BUSY_TX)
1686 /* Disable the DMA transfer for transmit request by resetting the DMAT bit
1687 in the USART CR3 register */
1688 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1690 /* Enable the USART Transmit Complete Interrupt */
1691 SET_BIT(husart->Instance->CR1, USART_CR1_TCIE);
1694 /* DMA Circular mode */
1695 else
1697 if(husart->State == HAL_USART_STATE_BUSY_TX)
1699 HAL_USART_TxCpltCallback(husart);
1706 * @brief DMA USART transmit process half complete callback
1707 * @param hdma : DMA handle
1708 * @retval None
1710 static void USART_DMATxHalfCplt(DMA_HandleTypeDef *hdma)
1712 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1714 HAL_USART_TxHalfCpltCallback(husart);
1718 * @brief DMA USART receive process complete callback
1719 * @param hdma: DMA handle
1720 * @retval None
1722 static void USART_DMAReceiveCplt(DMA_HandleTypeDef *hdma)
1724 USART_HandleTypeDef* husart = ( USART_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1726 /* DMA Normal mode */
1727 if((hdma->Instance->CR & DMA_SxCR_CIRC) == 0U)
1729 husart->RxXferCount = 0U;
1731 /* Disable RXNE, PE and ERR (Frame error, noise error, overrun error) interrupts */
1732 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1733 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1735 /* Disable the DMA RX transfer for the receiver request by resetting the DMAR bit
1736 in USART CR3 register */
1737 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAR);
1738 /* similarly, disable the DMA TX transfer that was started to provide the
1739 clock to the slave device */
1740 CLEAR_BIT(husart->Instance->CR3, USART_CR3_DMAT);
1742 if(husart->State == HAL_USART_STATE_BUSY_RX)
1744 HAL_USART_RxCpltCallback(husart);
1746 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1747 else
1749 HAL_USART_TxRxCpltCallback(husart);
1751 husart->State= HAL_USART_STATE_READY;
1753 /* DMA circular mode */
1754 else
1756 if(husart->State == HAL_USART_STATE_BUSY_RX)
1758 HAL_USART_RxCpltCallback(husart);
1760 /* The USART state is HAL_USART_STATE_BUSY_TX_RX */
1761 else
1763 HAL_USART_TxRxCpltCallback(husart);
1769 * @brief DMA USART receive process half complete callback
1770 * @param hdma : DMA handle
1771 * @retval None
1773 static void USART_DMARxHalfCplt(DMA_HandleTypeDef *hdma)
1775 USART_HandleTypeDef* husart = (USART_HandleTypeDef*)((DMA_HandleTypeDef*)hdma)->Parent;
1777 HAL_USART_RxHalfCpltCallback(husart);
1781 * @brief DMA USART communication error callback
1782 * @param hdma: DMA handle
1783 * @retval None
1785 static void USART_DMAError(DMA_HandleTypeDef *hdma)
1787 USART_HandleTypeDef* husart = ( USART_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1789 husart->RxXferCount = 0U;
1790 husart->TxXferCount = 0U;
1792 /* Stop USART DMA Tx request if ongoing */
1793 if((husart->State == HAL_USART_STATE_BUSY_TX)
1794 &&(HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAT)))
1796 USART_EndTxTransfer(husart);
1799 /* Stop USART DMA Rx request if ongoing */
1800 if((husart->State == HAL_USART_STATE_BUSY_RX)
1801 &&(HAL_IS_BIT_SET(husart->Instance->CR3, USART_CR3_DMAR)))
1803 USART_EndRxTransfer(husart);
1806 husart->ErrorCode |= HAL_USART_ERROR_DMA;
1807 husart->State= HAL_USART_STATE_READY;
1809 HAL_USART_ErrorCallback(husart);
1813 * @brief DMA USART communication abort callback
1814 * (To be called at end of DMA Abort procedure).
1815 * @param hdma: DMA handle.
1816 * @retval None
1818 static void USART_DMAAbortOnError(DMA_HandleTypeDef *hdma)
1820 USART_HandleTypeDef* husart = (USART_HandleTypeDef* )((DMA_HandleTypeDef* )hdma)->Parent;
1821 husart->RxXferCount = 0U;
1822 husart->TxXferCount = 0U;
1824 HAL_USART_ErrorCallback(husart);
1828 * @brief End ongoing Tx transfer on USART peripheral (following error detection or Transmit completion).
1829 * @param husart: USART handle.
1830 * @retval None
1832 static void USART_EndTxTransfer(USART_HandleTypeDef *husart)
1834 /* At end of Tx process, restore husart->State to Ready */
1835 husart->State = HAL_USART_STATE_READY;
1837 /* Disable TXEIE and TCIE interrupts */
1838 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_TXEIE | USART_CR1_TCIE));
1842 * @brief End ongoing Rx transfer on USART peripheral (following error detection or Reception completion).
1843 * @param husart: USART handle.
1844 * @retval None
1846 static void USART_EndRxTransfer(USART_HandleTypeDef *husart)
1848 /* At end of Rx process, restore husart->RxState to Ready */
1849 husart->State = HAL_USART_STATE_READY;
1851 /* Disable RXNE, PE and ERR interrupts */
1852 CLEAR_BIT(husart->Instance->CR1, (USART_CR1_RXNEIE | USART_CR1_PEIE));
1853 CLEAR_BIT(husart->Instance->CR3, USART_CR3_EIE);
1857 * @brief Configure the USART peripheral
1858 * @param husart: USART handle
1859 * @retval None
1861 static HAL_StatusTypeDef USART_SetConfig(USART_HandleTypeDef *husart)
1863 uint32_t tmpreg = 0x0U;
1864 USART_ClockSourceTypeDef clocksource = USART_CLOCKSOURCE_UNDEFINED;
1865 HAL_StatusTypeDef ret = HAL_OK;
1866 uint16_t brrtemp = 0x0000U;
1867 uint16_t usartdiv = 0x0000U;
1869 /* Check the parameters */
1870 assert_param(IS_USART_POLARITY(husart->Init.CLKPolarity));
1871 assert_param(IS_USART_PHASE(husart->Init.CLKPhase));
1872 assert_param(IS_USART_LASTBIT(husart->Init.CLKLastBit));
1873 assert_param(IS_USART_BAUDRATE(husart->Init.BaudRate));
1874 assert_param(IS_USART_WORD_LENGTH(husart->Init.WordLength));
1875 assert_param(IS_USART_STOPBITS(husart->Init.StopBits));
1876 assert_param(IS_USART_PARITY(husart->Init.Parity));
1877 assert_param(IS_USART_MODE(husart->Init.Mode));
1878 assert_param(IS_USART_OVERSAMPLING(husart->Init.OverSampling));
1881 /*-------------------------- USART CR1 Configuration -----------------------*/
1882 /* Clear M, PCE, PS, TE and RE bits and configure
1883 * the USART Word Length, Parity, Mode and OverSampling:
1884 * set the M bits according to husart->Init.WordLength value
1885 * set PCE and PS bits according to husart->Init.Parity value
1886 * set TE and RE bits according to husart->Init.Mode value
1887 * force OVER8 to 1 to allow to reach the maximum speed (Fclock/8) */
1888 tmpreg = (uint32_t)husart->Init.WordLength | husart->Init.Parity | husart->Init.Mode | USART_CR1_OVER8;
1889 MODIFY_REG(husart->Instance->CR1, USART_CR1_FIELDS, tmpreg);
1891 /*---------------------------- USART CR2 Configuration ---------------------*/
1892 /* Clear and configure the USART Clock, CPOL, CPHA, LBCL and STOP bits:
1893 * set CPOL bit according to husart->Init.CLKPolarity value
1894 * set CPHA bit according to husart->Init.CLKPhase value
1895 * set LBCL bit according to husart->Init.CLKLastBit value
1896 * set STOP[13:12] bits according to husart->Init.StopBits value */
1897 tmpreg = (uint32_t)(USART_CLOCK_ENABLE);
1898 tmpreg |= ((uint32_t)husart->Init.CLKPolarity | (uint32_t)husart->Init.CLKPhase);
1899 tmpreg |= ((uint32_t)husart->Init.CLKLastBit | (uint32_t)husart->Init.StopBits);
1900 MODIFY_REG(husart->Instance->CR2, USART_CR2_FIELDS, tmpreg);
1902 /*-------------------------- USART CR3 Configuration -----------------------*/
1903 /* no CR3 register configuration */
1905 /*-------------------------- USART BRR Configuration -----------------------*/
1906 /* BRR is filled-up according to OVER8 bit setting which is forced to 1 */
1907 USART_GETCLOCKSOURCE(husart, clocksource);
1908 switch (clocksource)
1910 case USART_CLOCKSOURCE_PCLK1:
1911 usartdiv = (uint16_t)(((2*HAL_RCC_GetPCLK1Freq()) + (husart->Init.BaudRate/2))/ husart->Init.BaudRate);
1912 break;
1913 case USART_CLOCKSOURCE_PCLK2:
1914 usartdiv = (uint16_t)(((2*HAL_RCC_GetPCLK2Freq()) + (husart->Init.BaudRate/2))/ husart->Init.BaudRate);
1915 break;
1916 case USART_CLOCKSOURCE_HSI:
1917 usartdiv = (uint16_t)(((2*HSI_VALUE) + (husart->Init.BaudRate/2))/ husart->Init.BaudRate);
1918 break;
1919 case USART_CLOCKSOURCE_SYSCLK:
1920 usartdiv = (uint16_t)(((2*HAL_RCC_GetSysClockFreq()) + (husart->Init.BaudRate/2))/ husart->Init.BaudRate);
1921 break;
1922 case USART_CLOCKSOURCE_LSE:
1923 usartdiv = (uint16_t)(((2*LSE_VALUE) + (husart->Init.BaudRate/2))/ husart->Init.BaudRate);
1924 break;
1925 case USART_CLOCKSOURCE_UNDEFINED:
1926 default:
1927 ret = HAL_ERROR;
1928 break;
1931 brrtemp = usartdiv & 0xFFF0U;
1932 brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U);
1933 husart->Instance->BRR = brrtemp;
1935 return ret;
1939 * @brief Check the USART Idle State
1940 * @param husart: USART handle
1941 * @retval HAL status
1943 static HAL_StatusTypeDef USART_CheckIdleState(USART_HandleTypeDef *husart)
1945 uint32_t tickstart = 0U;
1947 /* Initialize the USART ErrorCode */
1948 husart->ErrorCode = HAL_USART_ERROR_NONE;
1950 /* Init tickstart for timeout managment*/
1951 tickstart = HAL_GetTick();
1953 /* Check if the Transmitter is enabled */
1954 if((husart->Instance->CR1 & USART_CR1_TE) == USART_CR1_TE)
1956 /* Wait until TEACK flag is set */
1957 if(USART_WaitOnFlagUntilTimeout(husart, USART_ISR_TEACK, RESET, tickstart, TEACK_REACK_TIMEOUT) != HAL_OK)
1959 husart->State= HAL_USART_STATE_TIMEOUT;
1960 return HAL_TIMEOUT;
1964 /* Initialize the USART state*/
1965 husart->State= HAL_USART_STATE_READY;
1967 /* Process Unlocked */
1968 __HAL_UNLOCK(husart);
1970 return HAL_OK;
1974 * @}
1977 #endif /* HAL_USART_MODULE_ENABLED */
1979 * @}
1983 * @}
1986 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/