2 ******************************************************************************
3 * @file stm32f4xx_ll_usart.h
4 * @author MCD Application Team
7 * @brief Header file of USART LL module.
8 ******************************************************************************
11 * <h2><center>© COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F4xx_LL_USART_H
40 #define __STM32F4xx_LL_USART_H
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f4xx.h"
49 /** @addtogroup STM32F4xx_LL_Driver
53 #if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10)
55 /** @defgroup USART_LL USART
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
62 /* Private constants ---------------------------------------------------------*/
63 /** @defgroup USART_LL_Private_Constants USART Private Constants
67 /* Defines used for the bit position in the register and perform offsets*/
68 #define USART_POSITION_GTPR_GT USART_GTPR_GT_Pos
73 /* Private macros ------------------------------------------------------------*/
74 #if defined(USE_FULL_LL_DRIVER)
75 /** @defgroup USART_LL_Private_Macros USART Private Macros
81 #endif /*USE_FULL_LL_DRIVER*/
83 /* Exported types ------------------------------------------------------------*/
84 #if defined(USE_FULL_LL_DRIVER)
85 /** @defgroup USART_LL_ES_INIT USART Exported Init structures
90 * @brief LL USART Init Structure definition
94 uint32_t BaudRate
; /*!< This field defines expected Usart communication baud rate.
96 This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/
98 uint32_t DataWidth
; /*!< Specifies the number of data bits transmitted or received in a frame.
99 This parameter can be a value of @ref USART_LL_EC_DATAWIDTH.
101 This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/
103 uint32_t StopBits
; /*!< Specifies the number of stop bits transmitted.
104 This parameter can be a value of @ref USART_LL_EC_STOPBITS.
106 This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/
108 uint32_t Parity
; /*!< Specifies the parity mode.
109 This parameter can be a value of @ref USART_LL_EC_PARITY.
111 This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/
113 uint32_t TransferDirection
; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled.
114 This parameter can be a value of @ref USART_LL_EC_DIRECTION.
116 This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/
118 uint32_t HardwareFlowControl
; /*!< Specifies whether the hardware flow control mode is enabled or disabled.
119 This parameter can be a value of @ref USART_LL_EC_HWCONTROL.
121 This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/
123 uint32_t OverSampling
; /*!< Specifies whether USART oversampling mode is 16 or 8.
124 This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING.
126 This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/
128 } LL_USART_InitTypeDef
;
131 * @brief LL USART Clock Init Structure definition
135 uint32_t ClockOutput
; /*!< Specifies whether the USART clock is enabled or disabled.
136 This parameter can be a value of @ref USART_LL_EC_CLOCK.
138 USART HW configuration can be modified afterwards using unitary functions
139 @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput().
140 For more details, refer to description of this function. */
142 uint32_t ClockPolarity
; /*!< Specifies the steady state of the serial clock.
143 This parameter can be a value of @ref USART_LL_EC_POLARITY.
145 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity().
146 For more details, refer to description of this function. */
148 uint32_t ClockPhase
; /*!< Specifies the clock transition on which the bit capture is made.
149 This parameter can be a value of @ref USART_LL_EC_PHASE.
151 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase().
152 For more details, refer to description of this function. */
154 uint32_t LastBitClockPulse
; /*!< Specifies whether the clock pulse corresponding to the last transmitted
155 data bit (MSB) has to be output on the SCLK pin in synchronous mode.
156 This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE.
158 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput().
159 For more details, refer to description of this function. */
161 } LL_USART_ClockInitTypeDef
;
166 #endif /* USE_FULL_LL_DRIVER */
168 /* Exported constants --------------------------------------------------------*/
169 /** @defgroup USART_LL_Exported_Constants USART Exported Constants
173 /** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines
174 * @brief Flags defines which can be used with LL_USART_ReadReg function
177 #define LL_USART_SR_PE USART_SR_PE /*!< Parity error flag */
178 #define LL_USART_SR_FE USART_SR_FE /*!< Framing error flag */
179 #define LL_USART_SR_NE USART_SR_NE /*!< Noise detected flag */
180 #define LL_USART_SR_ORE USART_SR_ORE /*!< Overrun error flag */
181 #define LL_USART_SR_IDLE USART_SR_IDLE /*!< Idle line detected flag */
182 #define LL_USART_SR_RXNE USART_SR_RXNE /*!< Read data register not empty flag */
183 #define LL_USART_SR_TC USART_SR_TC /*!< Transmission complete flag */
184 #define LL_USART_SR_TXE USART_SR_TXE /*!< Transmit data register empty flag */
185 #define LL_USART_SR_LBD USART_SR_LBD /*!< LIN break detection flag */
186 #define LL_USART_SR_CTS USART_SR_CTS /*!< CTS flag */
191 /** @defgroup USART_LL_EC_IT IT Defines
192 * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions
195 #define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */
196 #define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */
197 #define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */
198 #define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */
199 #define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */
200 #define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */
201 #define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */
202 #define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */
207 /** @defgroup USART_LL_EC_DIRECTION Communication Direction
210 #define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */
211 #define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */
212 #define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */
213 #define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */
218 /** @defgroup USART_LL_EC_PARITY Parity Control
221 #define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */
222 #define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */
223 #define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */
228 /** @defgroup USART_LL_EC_WAKEUP Wakeup
231 #define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */
232 #define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */
237 /** @defgroup USART_LL_EC_DATAWIDTH Datawidth
240 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
241 #define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
246 /** @defgroup USART_LL_EC_OVERSAMPLING Oversampling
249 #define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */
250 #define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */
255 #if defined(USE_FULL_LL_DRIVER)
256 /** @defgroup USART_LL_EC_CLOCK Clock Signal
260 #define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */
261 #define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */
265 #endif /*USE_FULL_LL_DRIVER*/
267 /** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse
270 #define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */
271 #define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */
276 /** @defgroup USART_LL_EC_PHASE Clock Phase
279 #define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */
280 #define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */
285 /** @defgroup USART_LL_EC_POLARITY Clock Polarity
288 #define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/
289 #define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */
294 /** @defgroup USART_LL_EC_STOPBITS Stop Bits
297 #define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */
298 #define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */
299 #define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */
300 #define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */
305 /** @defgroup USART_LL_EC_HWCONTROL Hardware Control
308 #define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */
309 #define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */
310 #define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */
311 #define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */
316 /** @defgroup USART_LL_EC_IRDA_POWER IrDA Power
319 #define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */
320 #define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */
325 /** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length
328 #define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */
329 #define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */
338 /* Exported macro ------------------------------------------------------------*/
339 /** @defgroup USART_LL_Exported_Macros USART Exported Macros
343 /** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros
348 * @brief Write a value in USART register
349 * @param __INSTANCE__ USART Instance
350 * @param __REG__ Register to be written
351 * @param __VALUE__ Value to be written in the register
354 #define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
357 * @brief Read a value in USART register
358 * @param __INSTANCE__ USART Instance
359 * @param __REG__ Register to be read
360 * @retval Register value
362 #define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
367 /** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
372 * @brief Compute USARTDIV value according to Peripheral Clock and
373 * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned)
374 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
375 * @param __BAUDRATE__ Baud rate value to achieve
376 * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case
378 #define __LL_USART_DIV_SAMPLING8_100(__PERIPHCLK__, __BAUDRATE__) (((__PERIPHCLK__)*25)/(2*(__BAUDRATE__)))
379 #define __LL_USART_DIVMANT_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__))/100)
380 #define __LL_USART_DIVFRAQ_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 8 + 50) / 100)
381 /* UART BRR = mantissa + overflow + fraction
382 = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */
383 #define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \
384 ((__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0xF8) << 1)) + \
385 (__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0x07))
388 * @brief Compute USARTDIV value according to Peripheral Clock and
389 * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned)
390 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
391 * @param __BAUDRATE__ Baud rate value to achieve
392 * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case
394 #define __LL_USART_DIV_SAMPLING16_100(__PERIPHCLK__, __BAUDRATE__) (((__PERIPHCLK__)*25)/(4*(__BAUDRATE__)))
395 #define __LL_USART_DIVMANT_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__))/100)
396 #define __LL_USART_DIVFRAQ_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 16 + 50) / 100)
397 /* USART BRR = mantissa + overflow + fraction
398 = (USART DIVMANT << 4) + (USART DIVFRAQ & 0xF0) + (USART DIVFRAQ & 0x0F) */
399 #define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \
400 (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0xF0)) + \
401 (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0x0F))
411 /* Exported functions --------------------------------------------------------*/
413 /** @defgroup USART_LL_Exported_Functions USART Exported Functions
417 /** @defgroup USART_LL_EF_Configuration Configuration functions
422 * @brief USART Enable
423 * @rmtoll CR1 UE LL_USART_Enable
424 * @param USARTx USART Instance
427 __STATIC_INLINE
void LL_USART_Enable(USART_TypeDef
*USARTx
)
429 SET_BIT(USARTx
->CR1
, USART_CR1_UE
);
433 * @brief USART Disable (all USART prescalers and outputs are disabled)
434 * @note When USART is disabled, USART prescalers and outputs are stopped immediately,
435 * and current operations are discarded. The configuration of the USART is kept, but all the status
436 * flags, in the USARTx_SR are set to their default values.
437 * @rmtoll CR1 UE LL_USART_Disable
438 * @param USARTx USART Instance
441 __STATIC_INLINE
void LL_USART_Disable(USART_TypeDef
*USARTx
)
443 CLEAR_BIT(USARTx
->CR1
, USART_CR1_UE
);
447 * @brief Indicate if USART is enabled
448 * @rmtoll CR1 UE LL_USART_IsEnabled
449 * @param USARTx USART Instance
450 * @retval State of bit (1 or 0).
452 __STATIC_INLINE
uint32_t LL_USART_IsEnabled(USART_TypeDef
*USARTx
)
454 return (READ_BIT(USARTx
->CR1
, USART_CR1_UE
) == (USART_CR1_UE
));
458 * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit)
459 * @rmtoll CR1 RE LL_USART_EnableDirectionRx
460 * @param USARTx USART Instance
463 __STATIC_INLINE
void LL_USART_EnableDirectionRx(USART_TypeDef
*USARTx
)
465 SET_BIT(USARTx
->CR1
, USART_CR1_RE
);
469 * @brief Receiver Disable
470 * @rmtoll CR1 RE LL_USART_DisableDirectionRx
471 * @param USARTx USART Instance
474 __STATIC_INLINE
void LL_USART_DisableDirectionRx(USART_TypeDef
*USARTx
)
476 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RE
);
480 * @brief Transmitter Enable
481 * @rmtoll CR1 TE LL_USART_EnableDirectionTx
482 * @param USARTx USART Instance
485 __STATIC_INLINE
void LL_USART_EnableDirectionTx(USART_TypeDef
*USARTx
)
487 SET_BIT(USARTx
->CR1
, USART_CR1_TE
);
491 * @brief Transmitter Disable
492 * @rmtoll CR1 TE LL_USART_DisableDirectionTx
493 * @param USARTx USART Instance
496 __STATIC_INLINE
void LL_USART_DisableDirectionTx(USART_TypeDef
*USARTx
)
498 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TE
);
502 * @brief Configure simultaneously enabled/disabled states
503 * of Transmitter and Receiver
504 * @rmtoll CR1 RE LL_USART_SetTransferDirection\n
505 * CR1 TE LL_USART_SetTransferDirection
506 * @param USARTx USART Instance
507 * @param TransferDirection This parameter can be one of the following values:
508 * @arg @ref LL_USART_DIRECTION_NONE
509 * @arg @ref LL_USART_DIRECTION_RX
510 * @arg @ref LL_USART_DIRECTION_TX
511 * @arg @ref LL_USART_DIRECTION_TX_RX
514 __STATIC_INLINE
void LL_USART_SetTransferDirection(USART_TypeDef
*USARTx
, uint32_t TransferDirection
)
516 MODIFY_REG(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
, TransferDirection
);
520 * @brief Return enabled/disabled states of Transmitter and Receiver
521 * @rmtoll CR1 RE LL_USART_GetTransferDirection\n
522 * CR1 TE LL_USART_GetTransferDirection
523 * @param USARTx USART Instance
524 * @retval Returned value can be one of the following values:
525 * @arg @ref LL_USART_DIRECTION_NONE
526 * @arg @ref LL_USART_DIRECTION_RX
527 * @arg @ref LL_USART_DIRECTION_TX
528 * @arg @ref LL_USART_DIRECTION_TX_RX
530 __STATIC_INLINE
uint32_t LL_USART_GetTransferDirection(USART_TypeDef
*USARTx
)
532 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
));
536 * @brief Configure Parity (enabled/disabled and parity mode if enabled).
537 * @note This function selects if hardware parity control (generation and detection) is enabled or disabled.
538 * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position
539 * (9th or 8th bit depending on data width) and parity is checked on the received data.
540 * @rmtoll CR1 PS LL_USART_SetParity\n
541 * CR1 PCE LL_USART_SetParity
542 * @param USARTx USART Instance
543 * @param Parity This parameter can be one of the following values:
544 * @arg @ref LL_USART_PARITY_NONE
545 * @arg @ref LL_USART_PARITY_EVEN
546 * @arg @ref LL_USART_PARITY_ODD
549 __STATIC_INLINE
void LL_USART_SetParity(USART_TypeDef
*USARTx
, uint32_t Parity
)
551 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
, Parity
);
555 * @brief Return Parity configuration (enabled/disabled and parity mode if enabled)
556 * @rmtoll CR1 PS LL_USART_GetParity\n
557 * CR1 PCE LL_USART_GetParity
558 * @param USARTx USART Instance
559 * @retval Returned value can be one of the following values:
560 * @arg @ref LL_USART_PARITY_NONE
561 * @arg @ref LL_USART_PARITY_EVEN
562 * @arg @ref LL_USART_PARITY_ODD
564 __STATIC_INLINE
uint32_t LL_USART_GetParity(USART_TypeDef
*USARTx
)
566 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
));
570 * @brief Set Receiver Wake Up method from Mute mode.
571 * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod
572 * @param USARTx USART Instance
573 * @param Method This parameter can be one of the following values:
574 * @arg @ref LL_USART_WAKEUP_IDLELINE
575 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
578 __STATIC_INLINE
void LL_USART_SetWakeUpMethod(USART_TypeDef
*USARTx
, uint32_t Method
)
580 MODIFY_REG(USARTx
->CR1
, USART_CR1_WAKE
, Method
);
584 * @brief Return Receiver Wake Up method from Mute mode
585 * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod
586 * @param USARTx USART Instance
587 * @retval Returned value can be one of the following values:
588 * @arg @ref LL_USART_WAKEUP_IDLELINE
589 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
591 __STATIC_INLINE
uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef
*USARTx
)
593 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_WAKE
));
597 * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits)
598 * @rmtoll CR1 M LL_USART_SetDataWidth
599 * @param USARTx USART Instance
600 * @param DataWidth This parameter can be one of the following values:
601 * @arg @ref LL_USART_DATAWIDTH_8B
602 * @arg @ref LL_USART_DATAWIDTH_9B
605 __STATIC_INLINE
void LL_USART_SetDataWidth(USART_TypeDef
*USARTx
, uint32_t DataWidth
)
607 MODIFY_REG(USARTx
->CR1
, USART_CR1_M
, DataWidth
);
611 * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits)
612 * @rmtoll CR1 M LL_USART_GetDataWidth
613 * @param USARTx USART Instance
614 * @retval Returned value can be one of the following values:
615 * @arg @ref LL_USART_DATAWIDTH_8B
616 * @arg @ref LL_USART_DATAWIDTH_9B
618 __STATIC_INLINE
uint32_t LL_USART_GetDataWidth(USART_TypeDef
*USARTx
)
620 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_M
));
624 * @brief Set Oversampling to 8-bit or 16-bit mode
625 * @rmtoll CR1 OVER8 LL_USART_SetOverSampling
626 * @param USARTx USART Instance
627 * @param OverSampling This parameter can be one of the following values:
628 * @arg @ref LL_USART_OVERSAMPLING_16
629 * @arg @ref LL_USART_OVERSAMPLING_8
632 __STATIC_INLINE
void LL_USART_SetOverSampling(USART_TypeDef
*USARTx
, uint32_t OverSampling
)
634 MODIFY_REG(USARTx
->CR1
, USART_CR1_OVER8
, OverSampling
);
638 * @brief Return Oversampling mode
639 * @rmtoll CR1 OVER8 LL_USART_GetOverSampling
640 * @param USARTx USART Instance
641 * @retval Returned value can be one of the following values:
642 * @arg @ref LL_USART_OVERSAMPLING_16
643 * @arg @ref LL_USART_OVERSAMPLING_8
645 __STATIC_INLINE
uint32_t LL_USART_GetOverSampling(USART_TypeDef
*USARTx
)
647 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_OVER8
));
651 * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not
652 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
653 * Synchronous mode is supported by the USARTx instance.
654 * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput
655 * @param USARTx USART Instance
656 * @param LastBitClockPulse This parameter can be one of the following values:
657 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
658 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
661 __STATIC_INLINE
void LL_USART_SetLastClkPulseOutput(USART_TypeDef
*USARTx
, uint32_t LastBitClockPulse
)
663 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBCL
, LastBitClockPulse
);
667 * @brief Retrieve Clock pulse of the last data bit output configuration
668 * (Last bit Clock pulse output to the SCLK pin or not)
669 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
670 * Synchronous mode is supported by the USARTx instance.
671 * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput
672 * @param USARTx USART Instance
673 * @retval Returned value can be one of the following values:
674 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
675 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
677 __STATIC_INLINE
uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef
*USARTx
)
679 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBCL
));
683 * @brief Select the phase of the clock output on the SCLK pin in synchronous mode
684 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
685 * Synchronous mode is supported by the USARTx instance.
686 * @rmtoll CR2 CPHA LL_USART_SetClockPhase
687 * @param USARTx USART Instance
688 * @param ClockPhase This parameter can be one of the following values:
689 * @arg @ref LL_USART_PHASE_1EDGE
690 * @arg @ref LL_USART_PHASE_2EDGE
693 __STATIC_INLINE
void LL_USART_SetClockPhase(USART_TypeDef
*USARTx
, uint32_t ClockPhase
)
695 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
, ClockPhase
);
699 * @brief Return phase of the clock output on the SCLK pin in synchronous mode
700 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
701 * Synchronous mode is supported by the USARTx instance.
702 * @rmtoll CR2 CPHA LL_USART_GetClockPhase
703 * @param USARTx USART Instance
704 * @retval Returned value can be one of the following values:
705 * @arg @ref LL_USART_PHASE_1EDGE
706 * @arg @ref LL_USART_PHASE_2EDGE
708 __STATIC_INLINE
uint32_t LL_USART_GetClockPhase(USART_TypeDef
*USARTx
)
710 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPHA
));
714 * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode
715 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
716 * Synchronous mode is supported by the USARTx instance.
717 * @rmtoll CR2 CPOL LL_USART_SetClockPolarity
718 * @param USARTx USART Instance
719 * @param ClockPolarity This parameter can be one of the following values:
720 * @arg @ref LL_USART_POLARITY_LOW
721 * @arg @ref LL_USART_POLARITY_HIGH
724 __STATIC_INLINE
void LL_USART_SetClockPolarity(USART_TypeDef
*USARTx
, uint32_t ClockPolarity
)
726 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPOL
, ClockPolarity
);
730 * @brief Return polarity of the clock output on the SCLK pin in synchronous mode
731 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
732 * Synchronous mode is supported by the USARTx instance.
733 * @rmtoll CR2 CPOL LL_USART_GetClockPolarity
734 * @param USARTx USART Instance
735 * @retval Returned value can be one of the following values:
736 * @arg @ref LL_USART_POLARITY_LOW
737 * @arg @ref LL_USART_POLARITY_HIGH
739 __STATIC_INLINE
uint32_t LL_USART_GetClockPolarity(USART_TypeDef
*USARTx
)
741 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPOL
));
745 * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse)
746 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
747 * Synchronous mode is supported by the USARTx instance.
748 * @note Call of this function is equivalent to following function call sequence :
749 * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function
750 * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function
751 * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function
752 * @rmtoll CR2 CPHA LL_USART_ConfigClock\n
753 * CR2 CPOL LL_USART_ConfigClock\n
754 * CR2 LBCL LL_USART_ConfigClock
755 * @param USARTx USART Instance
756 * @param Phase This parameter can be one of the following values:
757 * @arg @ref LL_USART_PHASE_1EDGE
758 * @arg @ref LL_USART_PHASE_2EDGE
759 * @param Polarity This parameter can be one of the following values:
760 * @arg @ref LL_USART_POLARITY_LOW
761 * @arg @ref LL_USART_POLARITY_HIGH
762 * @param LBCPOutput This parameter can be one of the following values:
763 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
764 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
767 __STATIC_INLINE
void LL_USART_ConfigClock(USART_TypeDef
*USARTx
, uint32_t Phase
, uint32_t Polarity
, uint32_t LBCPOutput
)
769 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
| USART_CR2_CPOL
| USART_CR2_LBCL
, Phase
| Polarity
| LBCPOutput
);
773 * @brief Enable Clock output on SCLK pin
774 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
775 * Synchronous mode is supported by the USARTx instance.
776 * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput
777 * @param USARTx USART Instance
780 __STATIC_INLINE
void LL_USART_EnableSCLKOutput(USART_TypeDef
*USARTx
)
782 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
786 * @brief Disable Clock output on SCLK pin
787 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
788 * Synchronous mode is supported by the USARTx instance.
789 * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput
790 * @param USARTx USART Instance
793 __STATIC_INLINE
void LL_USART_DisableSCLKOutput(USART_TypeDef
*USARTx
)
795 CLEAR_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
799 * @brief Indicate if Clock output on SCLK pin is enabled
800 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
801 * Synchronous mode is supported by the USARTx instance.
802 * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput
803 * @param USARTx USART Instance
804 * @retval State of bit (1 or 0).
806 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef
*USARTx
)
808 return (READ_BIT(USARTx
->CR2
, USART_CR2_CLKEN
) == (USART_CR2_CLKEN
));
812 * @brief Set the length of the stop bits
813 * @rmtoll CR2 STOP LL_USART_SetStopBitsLength
814 * @param USARTx USART Instance
815 * @param StopBits This parameter can be one of the following values:
816 * @arg @ref LL_USART_STOPBITS_0_5
817 * @arg @ref LL_USART_STOPBITS_1
818 * @arg @ref LL_USART_STOPBITS_1_5
819 * @arg @ref LL_USART_STOPBITS_2
822 __STATIC_INLINE
void LL_USART_SetStopBitsLength(USART_TypeDef
*USARTx
, uint32_t StopBits
)
824 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
828 * @brief Retrieve the length of the stop bits
829 * @rmtoll CR2 STOP LL_USART_GetStopBitsLength
830 * @param USARTx USART Instance
831 * @retval Returned value can be one of the following values:
832 * @arg @ref LL_USART_STOPBITS_0_5
833 * @arg @ref LL_USART_STOPBITS_1
834 * @arg @ref LL_USART_STOPBITS_1_5
835 * @arg @ref LL_USART_STOPBITS_2
837 __STATIC_INLINE
uint32_t LL_USART_GetStopBitsLength(USART_TypeDef
*USARTx
)
839 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_STOP
));
843 * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits)
844 * @note Call of this function is equivalent to following function call sequence :
845 * - Data Width configuration using @ref LL_USART_SetDataWidth() function
846 * - Parity Control and mode configuration using @ref LL_USART_SetParity() function
847 * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function
848 * @rmtoll CR1 PS LL_USART_ConfigCharacter\n
849 * CR1 PCE LL_USART_ConfigCharacter\n
850 * CR1 M LL_USART_ConfigCharacter\n
851 * CR2 STOP LL_USART_ConfigCharacter
852 * @param USARTx USART Instance
853 * @param DataWidth This parameter can be one of the following values:
854 * @arg @ref LL_USART_DATAWIDTH_8B
855 * @arg @ref LL_USART_DATAWIDTH_9B
856 * @param Parity This parameter can be one of the following values:
857 * @arg @ref LL_USART_PARITY_NONE
858 * @arg @ref LL_USART_PARITY_EVEN
859 * @arg @ref LL_USART_PARITY_ODD
860 * @param StopBits This parameter can be one of the following values:
861 * @arg @ref LL_USART_STOPBITS_0_5
862 * @arg @ref LL_USART_STOPBITS_1
863 * @arg @ref LL_USART_STOPBITS_1_5
864 * @arg @ref LL_USART_STOPBITS_2
867 __STATIC_INLINE
void LL_USART_ConfigCharacter(USART_TypeDef
*USARTx
, uint32_t DataWidth
, uint32_t Parity
,
870 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
| USART_CR1_M
, Parity
| DataWidth
);
871 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
875 * @brief Set Address of the USART node.
876 * @note This is used in multiprocessor communication during Mute mode or Stop mode,
877 * for wake up with address mark detection.
878 * @rmtoll CR2 ADD LL_USART_SetNodeAddress
879 * @param USARTx USART Instance
880 * @param NodeAddress 4 bit Address of the USART node.
883 __STATIC_INLINE
void LL_USART_SetNodeAddress(USART_TypeDef
*USARTx
, uint32_t NodeAddress
)
885 MODIFY_REG(USARTx
->CR2
, USART_CR2_ADD
, (NodeAddress
& USART_CR2_ADD
));
889 * @brief Return 4 bit Address of the USART node as set in ADD field of CR2.
890 * @note only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant)
891 * @rmtoll CR2 ADD LL_USART_GetNodeAddress
892 * @param USARTx USART Instance
893 * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255)
895 __STATIC_INLINE
uint32_t LL_USART_GetNodeAddress(USART_TypeDef
*USARTx
)
897 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ADD
));
901 * @brief Enable RTS HW Flow Control
902 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
903 * Hardware Flow control feature is supported by the USARTx instance.
904 * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl
905 * @param USARTx USART Instance
908 __STATIC_INLINE
void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
910 SET_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
914 * @brief Disable RTS HW Flow Control
915 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
916 * Hardware Flow control feature is supported by the USARTx instance.
917 * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl
918 * @param USARTx USART Instance
921 __STATIC_INLINE
void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
923 CLEAR_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
927 * @brief Enable CTS HW Flow Control
928 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
929 * Hardware Flow control feature is supported by the USARTx instance.
930 * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl
931 * @param USARTx USART Instance
934 __STATIC_INLINE
void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
936 SET_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
940 * @brief Disable CTS HW Flow Control
941 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
942 * Hardware Flow control feature is supported by the USARTx instance.
943 * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl
944 * @param USARTx USART Instance
947 __STATIC_INLINE
void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
949 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
953 * @brief Configure HW Flow Control mode (both CTS and RTS)
954 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
955 * Hardware Flow control feature is supported by the USARTx instance.
956 * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n
957 * CR3 CTSE LL_USART_SetHWFlowCtrl
958 * @param USARTx USART Instance
959 * @param HardwareFlowControl This parameter can be one of the following values:
960 * @arg @ref LL_USART_HWCONTROL_NONE
961 * @arg @ref LL_USART_HWCONTROL_RTS
962 * @arg @ref LL_USART_HWCONTROL_CTS
963 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
966 __STATIC_INLINE
void LL_USART_SetHWFlowCtrl(USART_TypeDef
*USARTx
, uint32_t HardwareFlowControl
)
968 MODIFY_REG(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
, HardwareFlowControl
);
972 * @brief Return HW Flow Control configuration (both CTS and RTS)
973 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
974 * Hardware Flow control feature is supported by the USARTx instance.
975 * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n
976 * CR3 CTSE LL_USART_GetHWFlowCtrl
977 * @param USARTx USART Instance
978 * @retval Returned value can be one of the following values:
979 * @arg @ref LL_USART_HWCONTROL_NONE
980 * @arg @ref LL_USART_HWCONTROL_RTS
981 * @arg @ref LL_USART_HWCONTROL_CTS
982 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
984 __STATIC_INLINE
uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef
*USARTx
)
986 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
));
990 * @brief Enable One bit sampling method
991 * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp
992 * @param USARTx USART Instance
995 __STATIC_INLINE
void LL_USART_EnableOneBitSamp(USART_TypeDef
*USARTx
)
997 SET_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1001 * @brief Disable One bit sampling method
1002 * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp
1003 * @param USARTx USART Instance
1006 __STATIC_INLINE
void LL_USART_DisableOneBitSamp(USART_TypeDef
*USARTx
)
1008 CLEAR_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1012 * @brief Indicate if One bit sampling method is enabled
1013 * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp
1014 * @param USARTx USART Instance
1015 * @retval State of bit (1 or 0).
1017 __STATIC_INLINE
uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef
*USARTx
)
1019 return (READ_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
) == (USART_CR3_ONEBIT
));
1023 * @brief Configure USART BRR register for achieving expected Baud Rate value.
1024 * @note Compute and set USARTDIV value in BRR Register (full BRR content)
1025 * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values
1026 * @note Peripheral clock and Baud rate values provided as function parameters should be valid
1027 * (Baud rate value != 0)
1028 * @rmtoll BRR BRR LL_USART_SetBaudRate
1029 * @param USARTx USART Instance
1030 * @param PeriphClk Peripheral Clock
1031 * @param OverSampling This parameter can be one of the following values:
1032 * @arg @ref LL_USART_OVERSAMPLING_16
1033 * @arg @ref LL_USART_OVERSAMPLING_8
1034 * @param BaudRate Baud Rate
1037 __STATIC_INLINE
void LL_USART_SetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t OverSampling
,
1040 if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1042 USARTx
->BRR
= (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk
, BaudRate
));
1046 USARTx
->BRR
= (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk
, BaudRate
));
1051 * @brief Return current Baud Rate value, according to USARTDIV present in BRR register
1052 * (full BRR content), and to used Peripheral Clock and Oversampling mode values
1053 * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned.
1054 * @rmtoll BRR BRR LL_USART_GetBaudRate
1055 * @param USARTx USART Instance
1056 * @param PeriphClk Peripheral Clock
1057 * @param OverSampling This parameter can be one of the following values:
1058 * @arg @ref LL_USART_OVERSAMPLING_16
1059 * @arg @ref LL_USART_OVERSAMPLING_8
1062 __STATIC_INLINE
uint32_t LL_USART_GetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t OverSampling
)
1064 register uint32_t usartdiv
= 0x0U
;
1065 register uint32_t brrresult
= 0x0U
;
1067 usartdiv
= USARTx
->BRR
;
1069 if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1071 if ((usartdiv
& 0xFFF7U
) != 0U)
1073 usartdiv
= (uint16_t)((usartdiv
& 0xFFF0U
) | ((usartdiv
& 0x0007U
) << 1U)) ;
1074 brrresult
= (PeriphClk
* 2U) / usartdiv
;
1079 if ((usartdiv
& 0xFFFFU
) != 0U)
1081 brrresult
= PeriphClk
/ usartdiv
;
1091 /** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature
1096 * @brief Enable IrDA mode
1097 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1098 * IrDA feature is supported by the USARTx instance.
1099 * @rmtoll CR3 IREN LL_USART_EnableIrda
1100 * @param USARTx USART Instance
1103 __STATIC_INLINE
void LL_USART_EnableIrda(USART_TypeDef
*USARTx
)
1105 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
1109 * @brief Disable IrDA mode
1110 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1111 * IrDA feature is supported by the USARTx instance.
1112 * @rmtoll CR3 IREN LL_USART_DisableIrda
1113 * @param USARTx USART Instance
1116 __STATIC_INLINE
void LL_USART_DisableIrda(USART_TypeDef
*USARTx
)
1118 CLEAR_BIT(USARTx
->CR3
, USART_CR3_IREN
);
1122 * @brief Indicate if IrDA mode is enabled
1123 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1124 * IrDA feature is supported by the USARTx instance.
1125 * @rmtoll CR3 IREN LL_USART_IsEnabledIrda
1126 * @param USARTx USART Instance
1127 * @retval State of bit (1 or 0).
1129 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIrda(USART_TypeDef
*USARTx
)
1131 return (READ_BIT(USARTx
->CR3
, USART_CR3_IREN
) == (USART_CR3_IREN
));
1135 * @brief Configure IrDA Power Mode (Normal or Low Power)
1136 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1137 * IrDA feature is supported by the USARTx instance.
1138 * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode
1139 * @param USARTx USART Instance
1140 * @param PowerMode This parameter can be one of the following values:
1141 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1142 * @arg @ref LL_USART_IRDA_POWER_LOW
1145 __STATIC_INLINE
void LL_USART_SetIrdaPowerMode(USART_TypeDef
*USARTx
, uint32_t PowerMode
)
1147 MODIFY_REG(USARTx
->CR3
, USART_CR3_IRLP
, PowerMode
);
1151 * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power)
1152 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1153 * IrDA feature is supported by the USARTx instance.
1154 * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode
1155 * @param USARTx USART Instance
1156 * @retval Returned value can be one of the following values:
1157 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1158 * @arg @ref LL_USART_PHASE_2EDGE
1160 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef
*USARTx
)
1162 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_IRLP
));
1166 * @brief Set Irda prescaler value, used for dividing the USART clock source
1167 * to achieve the Irda Low Power frequency (8 bits value)
1168 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1169 * IrDA feature is supported by the USARTx instance.
1170 * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler
1171 * @param USARTx USART Instance
1172 * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF
1175 __STATIC_INLINE
void LL_USART_SetIrdaPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
1177 MODIFY_REG(USARTx
->GTPR
, USART_GTPR_PSC
, PrescalerValue
);
1181 * @brief Return Irda prescaler value, used for dividing the USART clock source
1182 * to achieve the Irda Low Power frequency (8 bits value)
1183 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1184 * IrDA feature is supported by the USARTx instance.
1185 * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler
1186 * @param USARTx USART Instance
1187 * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF)
1189 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef
*USARTx
)
1191 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
1198 /** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature
1203 * @brief Enable Smartcard NACK transmission
1204 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1205 * Smartcard feature is supported by the USARTx instance.
1206 * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK
1207 * @param USARTx USART Instance
1210 __STATIC_INLINE
void LL_USART_EnableSmartcardNACK(USART_TypeDef
*USARTx
)
1212 SET_BIT(USARTx
->CR3
, USART_CR3_NACK
);
1216 * @brief Disable Smartcard NACK transmission
1217 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1218 * Smartcard feature is supported by the USARTx instance.
1219 * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK
1220 * @param USARTx USART Instance
1223 __STATIC_INLINE
void LL_USART_DisableSmartcardNACK(USART_TypeDef
*USARTx
)
1225 CLEAR_BIT(USARTx
->CR3
, USART_CR3_NACK
);
1229 * @brief Indicate if Smartcard NACK transmission is enabled
1230 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1231 * Smartcard feature is supported by the USARTx instance.
1232 * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK
1233 * @param USARTx USART Instance
1234 * @retval State of bit (1 or 0).
1236 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef
*USARTx
)
1238 return (READ_BIT(USARTx
->CR3
, USART_CR3_NACK
) == (USART_CR3_NACK
));
1242 * @brief Enable Smartcard mode
1243 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1244 * Smartcard feature is supported by the USARTx instance.
1245 * @rmtoll CR3 SCEN LL_USART_EnableSmartcard
1246 * @param USARTx USART Instance
1249 __STATIC_INLINE
void LL_USART_EnableSmartcard(USART_TypeDef
*USARTx
)
1251 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
1255 * @brief Disable Smartcard mode
1256 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1257 * Smartcard feature is supported by the USARTx instance.
1258 * @rmtoll CR3 SCEN LL_USART_DisableSmartcard
1259 * @param USARTx USART Instance
1262 __STATIC_INLINE
void LL_USART_DisableSmartcard(USART_TypeDef
*USARTx
)
1264 CLEAR_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
1268 * @brief Indicate if Smartcard mode is enabled
1269 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1270 * Smartcard feature is supported by the USARTx instance.
1271 * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard
1272 * @param USARTx USART Instance
1273 * @retval State of bit (1 or 0).
1275 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef
*USARTx
)
1277 return (READ_BIT(USARTx
->CR3
, USART_CR3_SCEN
) == (USART_CR3_SCEN
));
1281 * @brief Set Smartcard prescaler value, used for dividing the USART clock
1282 * source to provide the SMARTCARD Clock (5 bits value)
1283 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1284 * Smartcard feature is supported by the USARTx instance.
1285 * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler
1286 * @param USARTx USART Instance
1287 * @param PrescalerValue Value between Min_Data=0 and Max_Data=31
1290 __STATIC_INLINE
void LL_USART_SetSmartcardPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
1292 MODIFY_REG(USARTx
->GTPR
, USART_GTPR_PSC
, PrescalerValue
);
1296 * @brief Return Smartcard prescaler value, used for dividing the USART clock
1297 * source to provide the SMARTCARD Clock (5 bits value)
1298 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1299 * Smartcard feature is supported by the USARTx instance.
1300 * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler
1301 * @param USARTx USART Instance
1302 * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31)
1304 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef
*USARTx
)
1306 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
1310 * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods
1311 * (GT[7:0] bits : Guard time value)
1312 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1313 * Smartcard feature is supported by the USARTx instance.
1314 * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime
1315 * @param USARTx USART Instance
1316 * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF
1319 __STATIC_INLINE
void LL_USART_SetSmartcardGuardTime(USART_TypeDef
*USARTx
, uint32_t GuardTime
)
1321 MODIFY_REG(USARTx
->GTPR
, USART_GTPR_GT
, GuardTime
<< USART_POSITION_GTPR_GT
);
1325 * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods
1326 * (GT[7:0] bits : Guard time value)
1327 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1328 * Smartcard feature is supported by the USARTx instance.
1329 * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime
1330 * @param USARTx USART Instance
1331 * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF)
1333 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef
*USARTx
)
1335 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_GT
) >> USART_POSITION_GTPR_GT
);
1342 /** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature
1347 * @brief Enable Single Wire Half-Duplex mode
1348 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1349 * Half-Duplex mode is supported by the USARTx instance.
1350 * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex
1351 * @param USARTx USART Instance
1354 __STATIC_INLINE
void LL_USART_EnableHalfDuplex(USART_TypeDef
*USARTx
)
1356 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
1360 * @brief Disable Single Wire Half-Duplex mode
1361 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1362 * Half-Duplex mode is supported by the USARTx instance.
1363 * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex
1364 * @param USARTx USART Instance
1367 __STATIC_INLINE
void LL_USART_DisableHalfDuplex(USART_TypeDef
*USARTx
)
1369 CLEAR_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
1373 * @brief Indicate if Single Wire Half-Duplex mode is enabled
1374 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1375 * Half-Duplex mode is supported by the USARTx instance.
1376 * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex
1377 * @param USARTx USART Instance
1378 * @retval State of bit (1 or 0).
1380 __STATIC_INLINE
uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef
*USARTx
)
1382 return (READ_BIT(USARTx
->CR3
, USART_CR3_HDSEL
) == (USART_CR3_HDSEL
));
1389 /** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature
1394 * @brief Set LIN Break Detection Length
1395 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1396 * LIN feature is supported by the USARTx instance.
1397 * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen
1398 * @param USARTx USART Instance
1399 * @param LINBDLength This parameter can be one of the following values:
1400 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1401 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1404 __STATIC_INLINE
void LL_USART_SetLINBrkDetectionLen(USART_TypeDef
*USARTx
, uint32_t LINBDLength
)
1406 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBDL
, LINBDLength
);
1410 * @brief Return LIN Break Detection Length
1411 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1412 * LIN feature is supported by the USARTx instance.
1413 * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen
1414 * @param USARTx USART Instance
1415 * @retval Returned value can be one of the following values:
1416 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1417 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1419 __STATIC_INLINE
uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef
*USARTx
)
1421 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBDL
));
1425 * @brief Enable LIN mode
1426 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1427 * LIN feature is supported by the USARTx instance.
1428 * @rmtoll CR2 LINEN LL_USART_EnableLIN
1429 * @param USARTx USART Instance
1432 __STATIC_INLINE
void LL_USART_EnableLIN(USART_TypeDef
*USARTx
)
1434 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
1438 * @brief Disable LIN mode
1439 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1440 * LIN feature is supported by the USARTx instance.
1441 * @rmtoll CR2 LINEN LL_USART_DisableLIN
1442 * @param USARTx USART Instance
1445 __STATIC_INLINE
void LL_USART_DisableLIN(USART_TypeDef
*USARTx
)
1447 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
1451 * @brief Indicate if LIN mode is enabled
1452 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1453 * LIN feature is supported by the USARTx instance.
1454 * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN
1455 * @param USARTx USART Instance
1456 * @retval State of bit (1 or 0).
1458 __STATIC_INLINE
uint32_t LL_USART_IsEnabledLIN(USART_TypeDef
*USARTx
)
1460 return (READ_BIT(USARTx
->CR2
, USART_CR2_LINEN
) == (USART_CR2_LINEN
));
1467 /** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services
1472 * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART)
1473 * @note In UART mode, the following bits must be kept cleared:
1474 * - LINEN bit in the USART_CR2 register,
1475 * - CLKEN bit in the USART_CR2 register,
1476 * - SCEN bit in the USART_CR3 register,
1477 * - IREN bit in the USART_CR3 register,
1478 * - HDSEL bit in the USART_CR3 register.
1479 * @note Call of this function is equivalent to following function call sequence :
1480 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1481 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
1482 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1483 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1484 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1485 * @note Other remaining configurations items related to Asynchronous Mode
1486 * (as Baud Rate, Word length, Parity, ...) should be set using
1487 * dedicated functions
1488 * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n
1489 * CR2 CLKEN LL_USART_ConfigAsyncMode\n
1490 * CR3 SCEN LL_USART_ConfigAsyncMode\n
1491 * CR3 IREN LL_USART_ConfigAsyncMode\n
1492 * CR3 HDSEL LL_USART_ConfigAsyncMode
1493 * @param USARTx USART Instance
1496 __STATIC_INLINE
void LL_USART_ConfigAsyncMode(USART_TypeDef
*USARTx
)
1498 /* In Asynchronous mode, the following bits must be kept cleared:
1499 - LINEN, CLKEN bits in the USART_CR2 register,
1500 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
1501 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
1502 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
1506 * @brief Perform basic configuration of USART for enabling use in Synchronous Mode
1507 * @note In Synchronous mode, the following bits must be kept cleared:
1508 * - LINEN bit in the USART_CR2 register,
1509 * - SCEN bit in the USART_CR3 register,
1510 * - IREN bit in the USART_CR3 register,
1511 * - HDSEL bit in the USART_CR3 register.
1512 * This function also sets the USART in Synchronous mode.
1513 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1514 * Synchronous mode is supported by the USARTx instance.
1515 * @note Call of this function is equivalent to following function call sequence :
1516 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1517 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1518 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1519 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1520 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
1521 * @note Other remaining configurations items related to Synchronous Mode
1522 * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using
1523 * dedicated functions
1524 * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n
1525 * CR2 CLKEN LL_USART_ConfigSyncMode\n
1526 * CR3 SCEN LL_USART_ConfigSyncMode\n
1527 * CR3 IREN LL_USART_ConfigSyncMode\n
1528 * CR3 HDSEL LL_USART_ConfigSyncMode
1529 * @param USARTx USART Instance
1532 __STATIC_INLINE
void LL_USART_ConfigSyncMode(USART_TypeDef
*USARTx
)
1534 /* In Synchronous mode, the following bits must be kept cleared:
1535 - LINEN bit in the USART_CR2 register,
1536 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
1537 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
1538 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
1539 /* set the UART/USART in Synchronous mode */
1540 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
1544 * @brief Perform basic configuration of USART for enabling use in LIN Mode
1545 * @note In LIN mode, the following bits must be kept cleared:
1546 * - STOP and CLKEN bits in the USART_CR2 register,
1547 * - SCEN bit in the USART_CR3 register,
1548 * - IREN bit in the USART_CR3 register,
1549 * - HDSEL bit in the USART_CR3 register.
1550 * This function also set the UART/USART in LIN mode.
1551 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1552 * LIN feature is supported by the USARTx instance.
1553 * @note Call of this function is equivalent to following function call sequence :
1554 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
1555 * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
1556 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1557 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1558 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1559 * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function
1560 * @note Other remaining configurations items related to LIN Mode
1561 * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using
1562 * dedicated functions
1563 * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n
1564 * CR2 STOP LL_USART_ConfigLINMode\n
1565 * CR2 LINEN LL_USART_ConfigLINMode\n
1566 * CR3 IREN LL_USART_ConfigLINMode\n
1567 * CR3 SCEN LL_USART_ConfigLINMode\n
1568 * CR3 HDSEL LL_USART_ConfigLINMode
1569 * @param USARTx USART Instance
1572 __STATIC_INLINE
void LL_USART_ConfigLINMode(USART_TypeDef
*USARTx
)
1574 /* In LIN mode, the following bits must be kept cleared:
1575 - STOP and CLKEN bits in the USART_CR2 register,
1576 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
1577 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_CLKEN
| USART_CR2_STOP
));
1578 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_SCEN
| USART_CR3_HDSEL
));
1579 /* Set the UART/USART in LIN mode */
1580 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
1584 * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode
1585 * @note In Half Duplex mode, the following bits must be kept cleared:
1586 * - LINEN bit in the USART_CR2 register,
1587 * - CLKEN bit in the USART_CR2 register,
1588 * - SCEN bit in the USART_CR3 register,
1589 * - IREN bit in the USART_CR3 register,
1590 * This function also sets the UART/USART in Half Duplex mode.
1591 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1592 * Half-Duplex mode is supported by the USARTx instance.
1593 * @note Call of this function is equivalent to following function call sequence :
1594 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1595 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
1596 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1597 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1598 * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function
1599 * @note Other remaining configurations items related to Half Duplex Mode
1600 * (as Baud Rate, Word length, Parity, ...) should be set using
1601 * dedicated functions
1602 * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n
1603 * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n
1604 * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n
1605 * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n
1606 * CR3 IREN LL_USART_ConfigHalfDuplexMode
1607 * @param USARTx USART Instance
1610 __STATIC_INLINE
void LL_USART_ConfigHalfDuplexMode(USART_TypeDef
*USARTx
)
1612 /* In Half Duplex mode, the following bits must be kept cleared:
1613 - LINEN and CLKEN bits in the USART_CR2 register,
1614 - SCEN and IREN bits in the USART_CR3 register.*/
1615 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
1616 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
));
1617 /* set the UART/USART in Half Duplex mode */
1618 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
1622 * @brief Perform basic configuration of USART for enabling use in Smartcard Mode
1623 * @note In Smartcard mode, the following bits must be kept cleared:
1624 * - LINEN bit in the USART_CR2 register,
1625 * - IREN bit in the USART_CR3 register,
1626 * - HDSEL bit in the USART_CR3 register.
1627 * This function also configures Stop bits to 1.5 bits and
1628 * sets the USART in Smartcard mode (SCEN bit).
1629 * Clock Output is also enabled (CLKEN).
1630 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1631 * Smartcard feature is supported by the USARTx instance.
1632 * @note Call of this function is equivalent to following function call sequence :
1633 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1634 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1635 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1636 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
1637 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
1638 * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function
1639 * @note Other remaining configurations items related to Smartcard Mode
1640 * (as Baud Rate, Word length, Parity, ...) should be set using
1641 * dedicated functions
1642 * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n
1643 * CR2 STOP LL_USART_ConfigSmartcardMode\n
1644 * CR2 CLKEN LL_USART_ConfigSmartcardMode\n
1645 * CR3 HDSEL LL_USART_ConfigSmartcardMode\n
1646 * CR3 SCEN LL_USART_ConfigSmartcardMode
1647 * @param USARTx USART Instance
1650 __STATIC_INLINE
void LL_USART_ConfigSmartcardMode(USART_TypeDef
*USARTx
)
1652 /* In Smartcard mode, the following bits must be kept cleared:
1653 - LINEN bit in the USART_CR2 register,
1654 - IREN and HDSEL bits in the USART_CR3 register.*/
1655 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
1656 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_HDSEL
));
1657 /* Configure Stop bits to 1.5 bits */
1658 /* Synchronous mode is activated by default */
1659 SET_BIT(USARTx
->CR2
, (USART_CR2_STOP_0
| USART_CR2_STOP_1
| USART_CR2_CLKEN
));
1660 /* set the UART/USART in Smartcard mode */
1661 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
1665 * @brief Perform basic configuration of USART for enabling use in Irda Mode
1666 * @note In IRDA mode, the following bits must be kept cleared:
1667 * - LINEN bit in the USART_CR2 register,
1668 * - STOP and CLKEN bits in the USART_CR2 register,
1669 * - SCEN bit in the USART_CR3 register,
1670 * - HDSEL bit in the USART_CR3 register.
1671 * This function also sets the UART/USART in IRDA mode (IREN bit).
1672 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1673 * IrDA feature is supported by the USARTx instance.
1674 * @note Call of this function is equivalent to following function call sequence :
1675 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1676 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
1677 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1678 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1679 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
1680 * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function
1681 * @note Other remaining configurations items related to Irda Mode
1682 * (as Baud Rate, Word length, Power mode, ...) should be set using
1683 * dedicated functions
1684 * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n
1685 * CR2 CLKEN LL_USART_ConfigIrdaMode\n
1686 * CR2 STOP LL_USART_ConfigIrdaMode\n
1687 * CR3 SCEN LL_USART_ConfigIrdaMode\n
1688 * CR3 HDSEL LL_USART_ConfigIrdaMode\n
1689 * CR3 IREN LL_USART_ConfigIrdaMode
1690 * @param USARTx USART Instance
1693 __STATIC_INLINE
void LL_USART_ConfigIrdaMode(USART_TypeDef
*USARTx
)
1695 /* In IRDA mode, the following bits must be kept cleared:
1696 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
1697 - SCEN and HDSEL bits in the USART_CR3 register.*/
1698 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
| USART_CR2_STOP
));
1699 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
));
1700 /* set the UART/USART in IRDA mode */
1701 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
1705 * @brief Perform basic configuration of USART for enabling use in Multi processor Mode
1706 * (several USARTs connected in a network, one of the USARTs can be the master,
1707 * its TX output connected to the RX inputs of the other slaves USARTs).
1708 * @note In MultiProcessor mode, the following bits must be kept cleared:
1709 * - LINEN bit in the USART_CR2 register,
1710 * - CLKEN bit in the USART_CR2 register,
1711 * - SCEN bit in the USART_CR3 register,
1712 * - IREN bit in the USART_CR3 register,
1713 * - HDSEL bit in the USART_CR3 register.
1714 * @note Call of this function is equivalent to following function call sequence :
1715 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
1716 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
1717 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
1718 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
1719 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
1720 * @note Other remaining configurations items related to Multi processor Mode
1721 * (as Baud Rate, Wake Up Method, Node address, ...) should be set using
1722 * dedicated functions
1723 * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n
1724 * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n
1725 * CR3 SCEN LL_USART_ConfigMultiProcessMode\n
1726 * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n
1727 * CR3 IREN LL_USART_ConfigMultiProcessMode
1728 * @param USARTx USART Instance
1731 __STATIC_INLINE
void LL_USART_ConfigMultiProcessMode(USART_TypeDef
*USARTx
)
1733 /* In Multi Processor mode, the following bits must be kept cleared:
1734 - LINEN and CLKEN bits in the USART_CR2 register,
1735 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
1736 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
1737 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
| USART_CR3_IREN
));
1744 /** @defgroup USART_LL_EF_FLAG_Management FLAG_Management
1749 * @brief Check if the USART Parity Error Flag is set or not
1750 * @rmtoll SR PE LL_USART_IsActiveFlag_PE
1751 * @param USARTx USART Instance
1752 * @retval State of bit (1 or 0).
1754 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef
*USARTx
)
1756 return (READ_BIT(USARTx
->SR
, USART_SR_PE
) == (USART_SR_PE
));
1760 * @brief Check if the USART Framing Error Flag is set or not
1761 * @rmtoll SR FE LL_USART_IsActiveFlag_FE
1762 * @param USARTx USART Instance
1763 * @retval State of bit (1 or 0).
1765 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef
*USARTx
)
1767 return (READ_BIT(USARTx
->SR
, USART_SR_FE
) == (USART_SR_FE
));
1771 * @brief Check if the USART Noise error detected Flag is set or not
1772 * @rmtoll SR NF LL_USART_IsActiveFlag_NE
1773 * @param USARTx USART Instance
1774 * @retval State of bit (1 or 0).
1776 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef
*USARTx
)
1778 return (READ_BIT(USARTx
->SR
, USART_SR_NE
) == (USART_SR_NE
));
1782 * @brief Check if the USART OverRun Error Flag is set or not
1783 * @rmtoll SR ORE LL_USART_IsActiveFlag_ORE
1784 * @param USARTx USART Instance
1785 * @retval State of bit (1 or 0).
1787 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef
*USARTx
)
1789 return (READ_BIT(USARTx
->SR
, USART_SR_ORE
) == (USART_SR_ORE
));
1793 * @brief Check if the USART IDLE line detected Flag is set or not
1794 * @rmtoll SR IDLE LL_USART_IsActiveFlag_IDLE
1795 * @param USARTx USART Instance
1796 * @retval State of bit (1 or 0).
1798 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef
*USARTx
)
1800 return (READ_BIT(USARTx
->SR
, USART_SR_IDLE
) == (USART_SR_IDLE
));
1804 * @brief Check if the USART Read Data Register Not Empty Flag is set or not
1805 * @rmtoll SR RXNE LL_USART_IsActiveFlag_RXNE
1806 * @param USARTx USART Instance
1807 * @retval State of bit (1 or 0).
1809 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef
*USARTx
)
1811 return (READ_BIT(USARTx
->SR
, USART_SR_RXNE
) == (USART_SR_RXNE
));
1815 * @brief Check if the USART Transmission Complete Flag is set or not
1816 * @rmtoll SR TC LL_USART_IsActiveFlag_TC
1817 * @param USARTx USART Instance
1818 * @retval State of bit (1 or 0).
1820 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef
*USARTx
)
1822 return (READ_BIT(USARTx
->SR
, USART_SR_TC
) == (USART_SR_TC
));
1826 * @brief Check if the USART Transmit Data Register Empty Flag is set or not
1827 * @rmtoll SR TXE LL_USART_IsActiveFlag_TXE
1828 * @param USARTx USART Instance
1829 * @retval State of bit (1 or 0).
1831 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef
*USARTx
)
1833 return (READ_BIT(USARTx
->SR
, USART_SR_TXE
) == (USART_SR_TXE
));
1837 * @brief Check if the USART LIN Break Detection Flag is set or not
1838 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1839 * LIN feature is supported by the USARTx instance.
1840 * @rmtoll SR LBD LL_USART_IsActiveFlag_LBD
1841 * @param USARTx USART Instance
1842 * @retval State of bit (1 or 0).
1844 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef
*USARTx
)
1846 return (READ_BIT(USARTx
->SR
, USART_SR_LBD
) == (USART_SR_LBD
));
1850 * @brief Check if the USART CTS Flag is set or not
1851 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1852 * Hardware Flow control feature is supported by the USARTx instance.
1853 * @rmtoll SR CTS LL_USART_IsActiveFlag_nCTS
1854 * @param USARTx USART Instance
1855 * @retval State of bit (1 or 0).
1857 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef
*USARTx
)
1859 return (READ_BIT(USARTx
->SR
, USART_SR_CTS
) == (USART_SR_CTS
));
1863 * @brief Check if the USART Send Break Flag is set or not
1864 * @rmtoll CR1 SBK LL_USART_IsActiveFlag_SBK
1865 * @param USARTx USART Instance
1866 * @retval State of bit (1 or 0).
1868 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef
*USARTx
)
1870 return (READ_BIT(USARTx
->CR1
, USART_CR1_SBK
) == (USART_CR1_SBK
));
1874 * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not
1875 * @rmtoll CR1 RWU LL_USART_IsActiveFlag_RWU
1876 * @param USARTx USART Instance
1877 * @retval State of bit (1 or 0).
1879 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef
*USARTx
)
1881 return (READ_BIT(USARTx
->CR1
, USART_CR1_RWU
) == (USART_CR1_RWU
));
1885 * @brief Clear Parity Error Flag
1886 * @note Clearing this flag is done by a read access to the USARTx_SR
1887 * register followed by a read access to the USARTx_DR register.
1888 * @note Please also consider that when clearing this flag, other flags as
1889 * NE, FE, ORE, IDLE would also be cleared.
1890 * @rmtoll SR PE LL_USART_ClearFlag_PE
1891 * @param USARTx USART Instance
1894 __STATIC_INLINE
void LL_USART_ClearFlag_PE(USART_TypeDef
*USARTx
)
1896 __IO
uint32_t tmpreg
;
1897 tmpreg
= USARTx
->SR
;
1899 tmpreg
= USARTx
->DR
;
1904 * @brief Clear Framing Error Flag
1905 * @note Clearing this flag is done by a read access to the USARTx_SR
1906 * register followed by a read access to the USARTx_DR register.
1907 * @note Please also consider that when clearing this flag, other flags as
1908 * PE, NE, ORE, IDLE would also be cleared.
1909 * @rmtoll SR FE LL_USART_ClearFlag_FE
1910 * @param USARTx USART Instance
1913 __STATIC_INLINE
void LL_USART_ClearFlag_FE(USART_TypeDef
*USARTx
)
1915 __IO
uint32_t tmpreg
;
1916 tmpreg
= USARTx
->SR
;
1918 tmpreg
= USARTx
->DR
;
1923 * @brief Clear Noise detected Flag
1924 * @note Clearing this flag is done by a read access to the USARTx_SR
1925 * register followed by a read access to the USARTx_DR register.
1926 * @note Please also consider that when clearing this flag, other flags as
1927 * PE, FE, ORE, IDLE would also be cleared.
1928 * @rmtoll SR NF LL_USART_ClearFlag_NE
1929 * @param USARTx USART Instance
1932 __STATIC_INLINE
void LL_USART_ClearFlag_NE(USART_TypeDef
*USARTx
)
1934 __IO
uint32_t tmpreg
;
1935 tmpreg
= USARTx
->SR
;
1937 tmpreg
= USARTx
->DR
;
1942 * @brief Clear OverRun Error Flag
1943 * @note Clearing this flag is done by a read access to the USARTx_SR
1944 * register followed by a read access to the USARTx_DR register.
1945 * @note Please also consider that when clearing this flag, other flags as
1946 * PE, NE, FE, IDLE would also be cleared.
1947 * @rmtoll SR ORE LL_USART_ClearFlag_ORE
1948 * @param USARTx USART Instance
1951 __STATIC_INLINE
void LL_USART_ClearFlag_ORE(USART_TypeDef
*USARTx
)
1953 __IO
uint32_t tmpreg
;
1954 tmpreg
= USARTx
->SR
;
1956 tmpreg
= USARTx
->DR
;
1961 * @brief Clear IDLE line detected Flag
1962 * @note Clearing this flag is done by a read access to the USARTx_SR
1963 * register followed by a read access to the USARTx_DR register.
1964 * @note Please also consider that when clearing this flag, other flags as
1965 * PE, NE, FE, ORE would also be cleared.
1966 * @rmtoll SR IDLE LL_USART_ClearFlag_IDLE
1967 * @param USARTx USART Instance
1970 __STATIC_INLINE
void LL_USART_ClearFlag_IDLE(USART_TypeDef
*USARTx
)
1972 __IO
uint32_t tmpreg
;
1973 tmpreg
= USARTx
->SR
;
1975 tmpreg
= USARTx
->DR
;
1980 * @brief Clear Transmission Complete Flag
1981 * @rmtoll SR TC LL_USART_ClearFlag_TC
1982 * @param USARTx USART Instance
1985 __STATIC_INLINE
void LL_USART_ClearFlag_TC(USART_TypeDef
*USARTx
)
1987 WRITE_REG(USARTx
->SR
, ~(USART_SR_TC
));
1991 * @brief Clear RX Not Empty Flag
1992 * @rmtoll SR RXNE LL_USART_ClearFlag_RXNE
1993 * @param USARTx USART Instance
1996 __STATIC_INLINE
void LL_USART_ClearFlag_RXNE(USART_TypeDef
*USARTx
)
1998 WRITE_REG(USARTx
->SR
, ~(USART_SR_RXNE
));
2002 * @brief Clear LIN Break Detection Flag
2003 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2004 * LIN feature is supported by the USARTx instance.
2005 * @rmtoll SR LBD LL_USART_ClearFlag_LBD
2006 * @param USARTx USART Instance
2009 __STATIC_INLINE
void LL_USART_ClearFlag_LBD(USART_TypeDef
*USARTx
)
2011 WRITE_REG(USARTx
->SR
, ~(USART_SR_LBD
));
2015 * @brief Clear CTS Interrupt Flag
2016 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2017 * Hardware Flow control feature is supported by the USARTx instance.
2018 * @rmtoll SR CTS LL_USART_ClearFlag_nCTS
2019 * @param USARTx USART Instance
2022 __STATIC_INLINE
void LL_USART_ClearFlag_nCTS(USART_TypeDef
*USARTx
)
2024 WRITE_REG(USARTx
->SR
, ~(USART_SR_CTS
));
2031 /** @defgroup USART_LL_EF_IT_Management IT_Management
2036 * @brief Enable IDLE Interrupt
2037 * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE
2038 * @param USARTx USART Instance
2041 __STATIC_INLINE
void LL_USART_EnableIT_IDLE(USART_TypeDef
*USARTx
)
2043 SET_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
2047 * @brief Enable RX Not Empty Interrupt
2048 * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE
2049 * @param USARTx USART Instance
2052 __STATIC_INLINE
void LL_USART_EnableIT_RXNE(USART_TypeDef
*USARTx
)
2054 SET_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
);
2058 * @brief Enable Transmission Complete Interrupt
2059 * @rmtoll CR1 TCIE LL_USART_EnableIT_TC
2060 * @param USARTx USART Instance
2063 __STATIC_INLINE
void LL_USART_EnableIT_TC(USART_TypeDef
*USARTx
)
2065 SET_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
2069 * @brief Enable TX Empty Interrupt
2070 * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE
2071 * @param USARTx USART Instance
2074 __STATIC_INLINE
void LL_USART_EnableIT_TXE(USART_TypeDef
*USARTx
)
2076 SET_BIT(USARTx
->CR1
, USART_CR1_TXEIE
);
2080 * @brief Enable Parity Error Interrupt
2081 * @rmtoll CR1 PEIE LL_USART_EnableIT_PE
2082 * @param USARTx USART Instance
2085 __STATIC_INLINE
void LL_USART_EnableIT_PE(USART_TypeDef
*USARTx
)
2087 SET_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
2091 * @brief Enable LIN Break Detection Interrupt
2092 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2093 * LIN feature is supported by the USARTx instance.
2094 * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD
2095 * @param USARTx USART Instance
2098 __STATIC_INLINE
void LL_USART_EnableIT_LBD(USART_TypeDef
*USARTx
)
2100 SET_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
2104 * @brief Enable Error Interrupt
2105 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
2106 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register).
2107 * 0: Interrupt is inhibited
2108 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register.
2109 * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR
2110 * @param USARTx USART Instance
2113 __STATIC_INLINE
void LL_USART_EnableIT_ERROR(USART_TypeDef
*USARTx
)
2115 SET_BIT(USARTx
->CR3
, USART_CR3_EIE
);
2119 * @brief Enable CTS Interrupt
2120 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2121 * Hardware Flow control feature is supported by the USARTx instance.
2122 * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS
2123 * @param USARTx USART Instance
2126 __STATIC_INLINE
void LL_USART_EnableIT_CTS(USART_TypeDef
*USARTx
)
2128 SET_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
2132 * @brief Disable IDLE Interrupt
2133 * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE
2134 * @param USARTx USART Instance
2137 __STATIC_INLINE
void LL_USART_DisableIT_IDLE(USART_TypeDef
*USARTx
)
2139 CLEAR_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
2143 * @brief Disable RX Not Empty Interrupt
2144 * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE
2145 * @param USARTx USART Instance
2148 __STATIC_INLINE
void LL_USART_DisableIT_RXNE(USART_TypeDef
*USARTx
)
2150 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
);
2154 * @brief Disable Transmission Complete Interrupt
2155 * @rmtoll CR1 TCIE LL_USART_DisableIT_TC
2156 * @param USARTx USART Instance
2159 __STATIC_INLINE
void LL_USART_DisableIT_TC(USART_TypeDef
*USARTx
)
2161 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
2165 * @brief Disable TX Empty Interrupt
2166 * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE
2167 * @param USARTx USART Instance
2170 __STATIC_INLINE
void LL_USART_DisableIT_TXE(USART_TypeDef
*USARTx
)
2172 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TXEIE
);
2176 * @brief Disable Parity Error Interrupt
2177 * @rmtoll CR1 PEIE LL_USART_DisableIT_PE
2178 * @param USARTx USART Instance
2181 __STATIC_INLINE
void LL_USART_DisableIT_PE(USART_TypeDef
*USARTx
)
2183 CLEAR_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
2187 * @brief Disable LIN Break Detection Interrupt
2188 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2189 * LIN feature is supported by the USARTx instance.
2190 * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD
2191 * @param USARTx USART Instance
2194 __STATIC_INLINE
void LL_USART_DisableIT_LBD(USART_TypeDef
*USARTx
)
2196 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
2200 * @brief Disable Error Interrupt
2201 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
2202 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register).
2203 * 0: Interrupt is inhibited
2204 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register.
2205 * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR
2206 * @param USARTx USART Instance
2209 __STATIC_INLINE
void LL_USART_DisableIT_ERROR(USART_TypeDef
*USARTx
)
2211 CLEAR_BIT(USARTx
->CR3
, USART_CR3_EIE
);
2215 * @brief Disable CTS Interrupt
2216 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2217 * Hardware Flow control feature is supported by the USARTx instance.
2218 * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS
2219 * @param USARTx USART Instance
2222 __STATIC_INLINE
void LL_USART_DisableIT_CTS(USART_TypeDef
*USARTx
)
2224 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
2228 * @brief Check if the USART IDLE Interrupt source is enabled or disabled.
2229 * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE
2230 * @param USARTx USART Instance
2231 * @retval State of bit (1 or 0).
2233 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef
*USARTx
)
2235 return (READ_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
) == (USART_CR1_IDLEIE
));
2239 * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled.
2240 * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE
2241 * @param USARTx USART Instance
2242 * @retval State of bit (1 or 0).
2244 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef
*USARTx
)
2246 return (READ_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
) == (USART_CR1_RXNEIE
));
2250 * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled.
2251 * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC
2252 * @param USARTx USART Instance
2253 * @retval State of bit (1 or 0).
2255 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef
*USARTx
)
2257 return (READ_BIT(USARTx
->CR1
, USART_CR1_TCIE
) == (USART_CR1_TCIE
));
2261 * @brief Check if the USART TX Empty Interrupt is enabled or disabled.
2262 * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE
2263 * @param USARTx USART Instance
2264 * @retval State of bit (1 or 0).
2266 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef
*USARTx
)
2268 return (READ_BIT(USARTx
->CR1
, USART_CR1_TXEIE
) == (USART_CR1_TXEIE
));
2272 * @brief Check if the USART Parity Error Interrupt is enabled or disabled.
2273 * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE
2274 * @param USARTx USART Instance
2275 * @retval State of bit (1 or 0).
2277 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef
*USARTx
)
2279 return (READ_BIT(USARTx
->CR1
, USART_CR1_PEIE
) == (USART_CR1_PEIE
));
2283 * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled.
2284 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2285 * LIN feature is supported by the USARTx instance.
2286 * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD
2287 * @param USARTx USART Instance
2288 * @retval State of bit (1 or 0).
2290 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef
*USARTx
)
2292 return (READ_BIT(USARTx
->CR2
, USART_CR2_LBDIE
) == (USART_CR2_LBDIE
));
2296 * @brief Check if the USART Error Interrupt is enabled or disabled.
2297 * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR
2298 * @param USARTx USART Instance
2299 * @retval State of bit (1 or 0).
2301 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef
*USARTx
)
2303 return (READ_BIT(USARTx
->CR3
, USART_CR3_EIE
) == (USART_CR3_EIE
));
2307 * @brief Check if the USART CTS Interrupt is enabled or disabled.
2308 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2309 * Hardware Flow control feature is supported by the USARTx instance.
2310 * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS
2311 * @param USARTx USART Instance
2312 * @retval State of bit (1 or 0).
2314 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef
*USARTx
)
2316 return (READ_BIT(USARTx
->CR3
, USART_CR3_CTSIE
) == (USART_CR3_CTSIE
));
2323 /** @defgroup USART_LL_EF_DMA_Management DMA_Management
2328 * @brief Enable DMA Mode for reception
2329 * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX
2330 * @param USARTx USART Instance
2333 __STATIC_INLINE
void LL_USART_EnableDMAReq_RX(USART_TypeDef
*USARTx
)
2335 SET_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
2339 * @brief Disable DMA Mode for reception
2340 * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX
2341 * @param USARTx USART Instance
2344 __STATIC_INLINE
void LL_USART_DisableDMAReq_RX(USART_TypeDef
*USARTx
)
2346 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
2350 * @brief Check if DMA Mode is enabled for reception
2351 * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX
2352 * @param USARTx USART Instance
2353 * @retval State of bit (1 or 0).
2355 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef
*USARTx
)
2357 return (READ_BIT(USARTx
->CR3
, USART_CR3_DMAR
) == (USART_CR3_DMAR
));
2361 * @brief Enable DMA Mode for transmission
2362 * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX
2363 * @param USARTx USART Instance
2366 __STATIC_INLINE
void LL_USART_EnableDMAReq_TX(USART_TypeDef
*USARTx
)
2368 SET_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
2372 * @brief Disable DMA Mode for transmission
2373 * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX
2374 * @param USARTx USART Instance
2377 __STATIC_INLINE
void LL_USART_DisableDMAReq_TX(USART_TypeDef
*USARTx
)
2379 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
2383 * @brief Check if DMA Mode is enabled for transmission
2384 * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX
2385 * @param USARTx USART Instance
2386 * @retval State of bit (1 or 0).
2388 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef
*USARTx
)
2390 return (READ_BIT(USARTx
->CR3
, USART_CR3_DMAT
) == (USART_CR3_DMAT
));
2394 * @brief Get the data register address used for DMA transfer
2395 * @rmtoll DR DR LL_USART_DMA_GetRegAddr
2396 * @note Address of Data Register is valid for both Transmit and Receive transfers.
2397 * @param USARTx USART Instance
2398 * @retval Address of data register
2400 __STATIC_INLINE
uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef
*USARTx
)
2402 /* return address of DR register */
2403 return ((uint32_t) &(USARTx
->DR
));
2410 /** @defgroup USART_LL_EF_Data_Management Data_Management
2415 * @brief Read Receiver Data register (Receive Data value, 8 bits)
2416 * @rmtoll DR DR LL_USART_ReceiveData8
2417 * @param USARTx USART Instance
2418 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
2420 __STATIC_INLINE
uint8_t LL_USART_ReceiveData8(USART_TypeDef
*USARTx
)
2422 return (uint8_t)(READ_BIT(USARTx
->DR
, USART_DR_DR
));
2426 * @brief Read Receiver Data register (Receive Data value, 9 bits)
2427 * @rmtoll DR DR LL_USART_ReceiveData9
2428 * @param USARTx USART Instance
2429 * @retval Value between Min_Data=0x00 and Max_Data=0x1FF
2431 __STATIC_INLINE
uint16_t LL_USART_ReceiveData9(USART_TypeDef
*USARTx
)
2433 return (uint16_t)(READ_BIT(USARTx
->DR
, USART_DR_DR
));
2437 * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits)
2438 * @rmtoll DR DR LL_USART_TransmitData8
2439 * @param USARTx USART Instance
2440 * @param Value between Min_Data=0x00 and Max_Data=0xFF
2443 __STATIC_INLINE
void LL_USART_TransmitData8(USART_TypeDef
*USARTx
, uint8_t Value
)
2449 * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits)
2450 * @rmtoll DR DR LL_USART_TransmitData9
2451 * @param USARTx USART Instance
2452 * @param Value between Min_Data=0x00 and Max_Data=0x1FF
2455 __STATIC_INLINE
void LL_USART_TransmitData9(USART_TypeDef
*USARTx
, uint16_t Value
)
2457 USARTx
->DR
= Value
& 0x1FFU
;
2464 /** @defgroup USART_LL_EF_Execution Execution
2469 * @brief Request Break sending
2470 * @rmtoll CR1 SBK LL_USART_RequestBreakSending
2471 * @param USARTx USART Instance
2474 __STATIC_INLINE
void LL_USART_RequestBreakSending(USART_TypeDef
*USARTx
)
2476 SET_BIT(USARTx
->CR1
, USART_CR1_SBK
);
2480 * @brief Put USART in Mute mode
2481 * @rmtoll CR1 RWU LL_USART_RequestEnterMuteMode
2482 * @param USARTx USART Instance
2485 __STATIC_INLINE
void LL_USART_RequestEnterMuteMode(USART_TypeDef
*USARTx
)
2487 SET_BIT(USARTx
->CR1
, USART_CR1_RWU
);
2491 * @brief Put USART in Active mode
2492 * @rmtoll CR1 RWU LL_USART_RequestExitMuteMode
2493 * @param USARTx USART Instance
2496 __STATIC_INLINE
void LL_USART_RequestExitMuteMode(USART_TypeDef
*USARTx
)
2498 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RWU
);
2505 #if defined(USE_FULL_LL_DRIVER)
2506 /** @defgroup USART_LL_EF_Init Initialization and de-initialization functions
2509 ErrorStatus
LL_USART_DeInit(USART_TypeDef
*USARTx
);
2510 ErrorStatus
LL_USART_Init(USART_TypeDef
*USARTx
, LL_USART_InitTypeDef
*USART_InitStruct
);
2511 void LL_USART_StructInit(LL_USART_InitTypeDef
*USART_InitStruct
);
2512 ErrorStatus
LL_USART_ClockInit(USART_TypeDef
*USARTx
, LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
2513 void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
2517 #endif /* USE_FULL_LL_DRIVER */
2527 #endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */
2537 #endif /* __STM32F4xx_LL_USART_H */
2539 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/