2 ******************************************************************************
3 * @file stm32f7xx_ll_usart.h
4 * @author MCD Application Team
5 * @brief Header file of USART LL module.
6 ******************************************************************************
9 * <h2><center>© Copyright (c) 2017 STMicroelectronics.
10 * All rights reserved.</center></h2>
12 * This software component is licensed by ST under BSD 3-Clause license,
13 * the "License"; You may not use this file except in compliance with the
14 * License. You may obtain a copy of the License at:
15 * opensource.org/licenses/BSD-3-Clause
17 ******************************************************************************
20 /* Define to prevent recursive inclusion -------------------------------------*/
21 #ifndef STM32F7xx_LL_USART_H
22 #define STM32F7xx_LL_USART_H
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32f7xx.h"
31 /** @addtogroup STM32F7xx_LL_Driver
35 #if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8)
37 /** @defgroup USART_LL USART
41 /* Private types -------------------------------------------------------------*/
42 /* Private variables ---------------------------------------------------------*/
44 /* Private constants ---------------------------------------------------------*/
45 /** @defgroup USART_LL_Private_Constants USART Private Constants
52 /* Private macros ------------------------------------------------------------*/
53 #if defined(USE_FULL_LL_DRIVER)
54 /** @defgroup USART_LL_Private_Macros USART Private Macros
60 #endif /*USE_FULL_LL_DRIVER*/
62 /* Exported types ------------------------------------------------------------*/
63 #if defined(USE_FULL_LL_DRIVER)
64 /** @defgroup USART_LL_ES_INIT USART Exported Init structures
69 * @brief LL USART Init Structure definition
74 uint32_t BaudRate
; /*!< This field defines expected Usart communication baud rate.
76 This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/
78 uint32_t DataWidth
; /*!< Specifies the number of data bits transmitted or received in a frame.
79 This parameter can be a value of @ref USART_LL_EC_DATAWIDTH.
81 This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/
83 uint32_t StopBits
; /*!< Specifies the number of stop bits transmitted.
84 This parameter can be a value of @ref USART_LL_EC_STOPBITS.
86 This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/
88 uint32_t Parity
; /*!< Specifies the parity mode.
89 This parameter can be a value of @ref USART_LL_EC_PARITY.
91 This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/
93 uint32_t TransferDirection
; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled.
94 This parameter can be a value of @ref USART_LL_EC_DIRECTION.
96 This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/
98 uint32_t HardwareFlowControl
; /*!< Specifies whether the hardware flow control mode is enabled or disabled.
99 This parameter can be a value of @ref USART_LL_EC_HWCONTROL.
101 This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/
103 uint32_t OverSampling
; /*!< Specifies whether USART oversampling mode is 16 or 8.
104 This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING.
106 This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/
108 } LL_USART_InitTypeDef
;
111 * @brief LL USART Clock Init Structure definition
115 uint32_t ClockOutput
; /*!< Specifies whether the USART clock is enabled or disabled.
116 This parameter can be a value of @ref USART_LL_EC_CLOCK.
118 USART HW configuration can be modified afterwards using unitary functions
119 @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput().
120 For more details, refer to description of this function. */
122 uint32_t ClockPolarity
; /*!< Specifies the steady state of the serial clock.
123 This parameter can be a value of @ref USART_LL_EC_POLARITY.
125 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity().
126 For more details, refer to description of this function. */
128 uint32_t ClockPhase
; /*!< Specifies the clock transition on which the bit capture is made.
129 This parameter can be a value of @ref USART_LL_EC_PHASE.
131 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase().
132 For more details, refer to description of this function. */
134 uint32_t LastBitClockPulse
; /*!< Specifies whether the clock pulse corresponding to the last transmitted
135 data bit (MSB) has to be output on the SCLK pin in synchronous mode.
136 This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE.
138 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput().
139 For more details, refer to description of this function. */
141 } LL_USART_ClockInitTypeDef
;
146 #endif /* USE_FULL_LL_DRIVER */
148 /* Exported constants --------------------------------------------------------*/
149 /** @defgroup USART_LL_Exported_Constants USART Exported Constants
153 /** @defgroup USART_LL_EC_CLEAR_FLAG Clear Flags Defines
154 * @brief Flags defines which can be used with LL_USART_WriteReg function
157 #define LL_USART_ICR_PECF USART_ICR_PECF /*!< Parity error flag */
158 #define LL_USART_ICR_FECF USART_ICR_FECF /*!< Framing error flag */
159 #define LL_USART_ICR_NCF USART_ICR_NCF /*!< Noise error detected flag */
160 #define LL_USART_ICR_ORECF USART_ICR_ORECF /*!< Overrun error flag */
161 #define LL_USART_ICR_IDLECF USART_ICR_IDLECF /*!< Idle line detected flag */
162 #define LL_USART_ICR_TCCF USART_ICR_TCCF /*!< Transmission complete flag */
163 #if defined(USART_TCBGT_SUPPORT)
164 #define LL_USART_ICR_TCBGTCF USART_ICR_TCBGTCF /*!< Transmission completed before guard time flag */
166 #define LL_USART_ICR_LBDCF USART_ICR_LBDCF /*!< LIN break detection flag */
167 #define LL_USART_ICR_CTSCF USART_ICR_CTSCF /*!< CTS flag */
168 #define LL_USART_ICR_RTOCF USART_ICR_RTOCF /*!< Receiver timeout flag */
169 #define LL_USART_ICR_EOBCF USART_ICR_EOBCF /*!< End of block flag */
170 #define LL_USART_ICR_CMCF USART_ICR_CMCF /*!< Character match flag */
175 /** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines
176 * @brief Flags defines which can be used with LL_USART_ReadReg function
179 #define LL_USART_ISR_PE USART_ISR_PE /*!< Parity error flag */
180 #define LL_USART_ISR_FE USART_ISR_FE /*!< Framing error flag */
181 #define LL_USART_ISR_NE USART_ISR_NE /*!< Noise detected flag */
182 #define LL_USART_ISR_ORE USART_ISR_ORE /*!< Overrun error flag */
183 #define LL_USART_ISR_IDLE USART_ISR_IDLE /*!< Idle line detected flag */
184 #define LL_USART_ISR_RXNE USART_ISR_RXNE /*!< Read data register not empty flag */
185 #define LL_USART_ISR_TC USART_ISR_TC /*!< Transmission complete flag */
186 #define LL_USART_ISR_TXE USART_ISR_TXE /*!< Transmit data register empty flag */
187 #define LL_USART_ISR_LBDF USART_ISR_LBDF /*!< LIN break detection flag */
188 #define LL_USART_ISR_CTSIF USART_ISR_CTSIF /*!< CTS interrupt flag */
189 #define LL_USART_ISR_CTS USART_ISR_CTS /*!< CTS flag */
190 #define LL_USART_ISR_RTOF USART_ISR_RTOF /*!< Receiver timeout flag */
191 #define LL_USART_ISR_EOBF USART_ISR_EOBF /*!< End of block flag */
192 #define LL_USART_ISR_ABRE USART_ISR_ABRE /*!< Auto baud rate error flag */
193 #define LL_USART_ISR_ABRF USART_ISR_ABRF /*!< Auto baud rate flag */
194 #define LL_USART_ISR_BUSY USART_ISR_BUSY /*!< Busy flag */
195 #define LL_USART_ISR_CMF USART_ISR_CMF /*!< Character match flag */
196 #define LL_USART_ISR_SBKF USART_ISR_SBKF /*!< Send break flag */
197 #define LL_USART_ISR_RWU USART_ISR_RWU /*!< Receiver wakeup from Mute mode flag */
198 #define LL_USART_ISR_TEACK USART_ISR_TEACK /*!< Transmit enable acknowledge flag */
199 #if defined(USART_TCBGT_SUPPORT)
200 #define LL_USART_ISR_TCBGT USART_ISR_TCBGT /*!< Transmission complete before guard time completion flag */
206 /** @defgroup USART_LL_EC_IT IT Defines
207 * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions
210 #define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */
211 #define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */
212 #define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */
213 #define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */
214 #define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */
215 #define LL_USART_CR1_CMIE USART_CR1_CMIE /*!< Character match interrupt enable */
216 #define LL_USART_CR1_RTOIE USART_CR1_RTOIE /*!< Receiver timeout interrupt enable */
217 #define LL_USART_CR1_EOBIE USART_CR1_EOBIE /*!< End of Block interrupt enable */
218 #define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */
219 #define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */
220 #define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */
221 #if defined(USART_TCBGT_SUPPORT)
222 #define LL_USART_CR3_TCBGTIE USART_CR3_TCBGTIE /*!< Transmission complete before guard time interrupt enable */
228 /** @defgroup USART_LL_EC_DIRECTION Communication Direction
231 #define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */
232 #define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */
233 #define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */
234 #define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */
239 /** @defgroup USART_LL_EC_PARITY Parity Control
242 #define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */
243 #define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */
244 #define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */
249 /** @defgroup USART_LL_EC_WAKEUP Wakeup
252 #define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */
253 #define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */
258 /** @defgroup USART_LL_EC_DATAWIDTH Datawidth
261 #define LL_USART_DATAWIDTH_7B USART_CR1_M1 /*!< 7 bits word length : Start bit, 7 data bits, n stop bits */
262 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
263 #define LL_USART_DATAWIDTH_9B USART_CR1_M0 /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
268 /** @defgroup USART_LL_EC_OVERSAMPLING Oversampling
271 #define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */
272 #define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */
277 #if defined(USE_FULL_LL_DRIVER)
278 /** @defgroup USART_LL_EC_CLOCK Clock Signal
282 #define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */
283 #define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */
287 #endif /*USE_FULL_LL_DRIVER*/
289 /** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse
292 #define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */
293 #define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */
298 /** @defgroup USART_LL_EC_PHASE Clock Phase
301 #define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */
302 #define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */
307 /** @defgroup USART_LL_EC_POLARITY Clock Polarity
310 #define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/
311 #define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */
316 /** @defgroup USART_LL_EC_STOPBITS Stop Bits
319 #define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */
320 #define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */
321 #define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */
322 #define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */
327 /** @defgroup USART_LL_EC_TXRX TX RX Pins Swap
330 #define LL_USART_TXRX_STANDARD 0x00000000U /*!< TX/RX pins are used as defined in standard pinout */
331 #define LL_USART_TXRX_SWAPPED (USART_CR2_SWAP) /*!< TX and RX pins functions are swapped. */
336 /** @defgroup USART_LL_EC_RXPIN_LEVEL RX Pin Active Level Inversion
339 #define LL_USART_RXPIN_LEVEL_STANDARD 0x00000000U /*!< RX pin signal works using the standard logic levels */
340 #define LL_USART_RXPIN_LEVEL_INVERTED (USART_CR2_RXINV) /*!< RX pin signal values are inverted. */
345 /** @defgroup USART_LL_EC_TXPIN_LEVEL TX Pin Active Level Inversion
348 #define LL_USART_TXPIN_LEVEL_STANDARD 0x00000000U /*!< TX pin signal works using the standard logic levels */
349 #define LL_USART_TXPIN_LEVEL_INVERTED (USART_CR2_TXINV) /*!< TX pin signal values are inverted. */
354 /** @defgroup USART_LL_EC_BINARY_LOGIC Binary Data Inversion
357 #define LL_USART_BINARY_LOGIC_POSITIVE 0x00000000U /*!< Logical data from the data register are send/received in positive/direct logic. (1=H, 0=L) */
358 #define LL_USART_BINARY_LOGIC_NEGATIVE USART_CR2_DATAINV /*!< Logical data from the data register are send/received in negative/inverse logic. (1=L, 0=H). The parity bit is also inverted. */
363 /** @defgroup USART_LL_EC_BITORDER Bit Order
366 #define LL_USART_BITORDER_LSBFIRST 0x00000000U /*!< data is transmitted/received with data bit 0 first, following the start bit */
367 #define LL_USART_BITORDER_MSBFIRST USART_CR2_MSBFIRST /*!< data is transmitted/received with the MSB first, following the start bit */
372 /** @defgroup USART_LL_EC_AUTOBAUD_DETECT_ON Autobaud Detection
375 #define LL_USART_AUTOBAUD_DETECT_ON_STARTBIT 0x00000000U /*!< Measurement of the start bit is used to detect the baud rate */
376 #define LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE USART_CR2_ABRMODE_0 /*!< Falling edge to falling edge measurement. Received frame must start with a single bit = 1 -> Frame = Start10xxxxxx */
377 #define LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME USART_CR2_ABRMODE_1 /*!< 0x7F frame detection */
378 #define LL_USART_AUTOBAUD_DETECT_ON_55_FRAME (USART_CR2_ABRMODE_1 | USART_CR2_ABRMODE_0) /*!< 0x55 frame detection */
383 /** @defgroup USART_LL_EC_ADDRESS_DETECT Address Length Detection
386 #define LL_USART_ADDRESS_DETECT_4B 0x00000000U /*!< 4-bit address detection method selected */
387 #define LL_USART_ADDRESS_DETECT_7B USART_CR2_ADDM7 /*!< 7-bit address detection (in 8-bit data mode) method selected */
392 /** @defgroup USART_LL_EC_HWCONTROL Hardware Control
395 #define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */
396 #define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */
397 #define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */
398 #define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */
403 /** @defgroup USART_LL_EC_IRDA_POWER IrDA Power
406 #define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */
407 #define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */
412 /** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length
415 #define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */
416 #define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */
421 /** @defgroup USART_LL_EC_DE_POLARITY Driver Enable Polarity
424 #define LL_USART_DE_POLARITY_HIGH 0x00000000U /*!< DE signal is active high */
425 #define LL_USART_DE_POLARITY_LOW USART_CR3_DEP /*!< DE signal is active low */
430 /** @defgroup USART_LL_EC_DMA_REG_DATA DMA Register Data
433 #define LL_USART_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for transmission */
434 #define LL_USART_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for reception */
443 /* Exported macro ------------------------------------------------------------*/
444 /** @defgroup USART_LL_Exported_Macros USART Exported Macros
448 /** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros
453 * @brief Write a value in USART register
454 * @param __INSTANCE__ USART Instance
455 * @param __REG__ Register to be written
456 * @param __VALUE__ Value to be written in the register
459 #define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
462 * @brief Read a value in USART register
463 * @param __INSTANCE__ USART Instance
464 * @param __REG__ Register to be read
465 * @retval Register value
467 #define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
472 /** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
477 * @brief Compute USARTDIV value according to Peripheral Clock and
478 * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned)
479 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
480 * @param __BAUDRATE__ Baud rate value to achieve
481 * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case
483 #define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__PERIPHCLK__)*2U) + ((__BAUDRATE__)/2U))/(__BAUDRATE__))
486 * @brief Compute USARTDIV value according to Peripheral Clock and
487 * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned)
488 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
489 * @param __BAUDRATE__ Baud rate value to achieve
490 * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case
492 #define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__PERIPHCLK__) + ((__BAUDRATE__)/2U))/(__BAUDRATE__))
502 /* Exported functions --------------------------------------------------------*/
504 /** @defgroup USART_LL_Exported_Functions USART Exported Functions
508 /** @defgroup USART_LL_EF_Configuration Configuration functions
513 * @brief USART Enable
514 * @rmtoll CR1 UE LL_USART_Enable
515 * @param USARTx USART Instance
518 __STATIC_INLINE
void LL_USART_Enable(USART_TypeDef
*USARTx
)
520 SET_BIT(USARTx
->CR1
, USART_CR1_UE
);
524 * @brief USART Disable (all USART prescalers and outputs are disabled)
525 * @note When USART is disabled, USART prescalers and outputs are stopped immediately,
526 * and current operations are discarded. The configuration of the USART is kept, but all the status
527 * flags, in the USARTx_ISR are set to their default values.
528 * @rmtoll CR1 UE LL_USART_Disable
529 * @param USARTx USART Instance
532 __STATIC_INLINE
void LL_USART_Disable(USART_TypeDef
*USARTx
)
534 CLEAR_BIT(USARTx
->CR1
, USART_CR1_UE
);
538 * @brief Indicate if USART is enabled
539 * @rmtoll CR1 UE LL_USART_IsEnabled
540 * @param USARTx USART Instance
541 * @retval State of bit (1 or 0).
543 __STATIC_INLINE
uint32_t LL_USART_IsEnabled(USART_TypeDef
*USARTx
)
545 return ((READ_BIT(USARTx
->CR1
, USART_CR1_UE
) == (USART_CR1_UE
)) ? 1UL : 0UL);
549 * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit)
550 * @rmtoll CR1 RE LL_USART_EnableDirectionRx
551 * @param USARTx USART Instance
554 __STATIC_INLINE
void LL_USART_EnableDirectionRx(USART_TypeDef
*USARTx
)
556 SET_BIT(USARTx
->CR1
, USART_CR1_RE
);
560 * @brief Receiver Disable
561 * @rmtoll CR1 RE LL_USART_DisableDirectionRx
562 * @param USARTx USART Instance
565 __STATIC_INLINE
void LL_USART_DisableDirectionRx(USART_TypeDef
*USARTx
)
567 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RE
);
571 * @brief Transmitter Enable
572 * @rmtoll CR1 TE LL_USART_EnableDirectionTx
573 * @param USARTx USART Instance
576 __STATIC_INLINE
void LL_USART_EnableDirectionTx(USART_TypeDef
*USARTx
)
578 SET_BIT(USARTx
->CR1
, USART_CR1_TE
);
582 * @brief Transmitter Disable
583 * @rmtoll CR1 TE LL_USART_DisableDirectionTx
584 * @param USARTx USART Instance
587 __STATIC_INLINE
void LL_USART_DisableDirectionTx(USART_TypeDef
*USARTx
)
589 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TE
);
593 * @brief Configure simultaneously enabled/disabled states
594 * of Transmitter and Receiver
595 * @rmtoll CR1 RE LL_USART_SetTransferDirection\n
596 * CR1 TE LL_USART_SetTransferDirection
597 * @param USARTx USART Instance
598 * @param TransferDirection This parameter can be one of the following values:
599 * @arg @ref LL_USART_DIRECTION_NONE
600 * @arg @ref LL_USART_DIRECTION_RX
601 * @arg @ref LL_USART_DIRECTION_TX
602 * @arg @ref LL_USART_DIRECTION_TX_RX
605 __STATIC_INLINE
void LL_USART_SetTransferDirection(USART_TypeDef
*USARTx
, uint32_t TransferDirection
)
607 MODIFY_REG(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
, TransferDirection
);
611 * @brief Return enabled/disabled states of Transmitter and Receiver
612 * @rmtoll CR1 RE LL_USART_GetTransferDirection\n
613 * CR1 TE LL_USART_GetTransferDirection
614 * @param USARTx USART Instance
615 * @retval Returned value can be one of the following values:
616 * @arg @ref LL_USART_DIRECTION_NONE
617 * @arg @ref LL_USART_DIRECTION_RX
618 * @arg @ref LL_USART_DIRECTION_TX
619 * @arg @ref LL_USART_DIRECTION_TX_RX
621 __STATIC_INLINE
uint32_t LL_USART_GetTransferDirection(USART_TypeDef
*USARTx
)
623 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
));
627 * @brief Configure Parity (enabled/disabled and parity mode if enabled).
628 * @note This function selects if hardware parity control (generation and detection) is enabled or disabled.
629 * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position
630 * (9th or 8th bit depending on data width) and parity is checked on the received data.
631 * @rmtoll CR1 PS LL_USART_SetParity\n
632 * CR1 PCE LL_USART_SetParity
633 * @param USARTx USART Instance
634 * @param Parity This parameter can be one of the following values:
635 * @arg @ref LL_USART_PARITY_NONE
636 * @arg @ref LL_USART_PARITY_EVEN
637 * @arg @ref LL_USART_PARITY_ODD
640 __STATIC_INLINE
void LL_USART_SetParity(USART_TypeDef
*USARTx
, uint32_t Parity
)
642 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
, Parity
);
646 * @brief Return Parity configuration (enabled/disabled and parity mode if enabled)
647 * @rmtoll CR1 PS LL_USART_GetParity\n
648 * CR1 PCE LL_USART_GetParity
649 * @param USARTx USART Instance
650 * @retval Returned value can be one of the following values:
651 * @arg @ref LL_USART_PARITY_NONE
652 * @arg @ref LL_USART_PARITY_EVEN
653 * @arg @ref LL_USART_PARITY_ODD
655 __STATIC_INLINE
uint32_t LL_USART_GetParity(USART_TypeDef
*USARTx
)
657 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
));
661 * @brief Set Receiver Wake Up method from Mute mode.
662 * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod
663 * @param USARTx USART Instance
664 * @param Method This parameter can be one of the following values:
665 * @arg @ref LL_USART_WAKEUP_IDLELINE
666 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
669 __STATIC_INLINE
void LL_USART_SetWakeUpMethod(USART_TypeDef
*USARTx
, uint32_t Method
)
671 MODIFY_REG(USARTx
->CR1
, USART_CR1_WAKE
, Method
);
675 * @brief Return Receiver Wake Up method from Mute mode
676 * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod
677 * @param USARTx USART Instance
678 * @retval Returned value can be one of the following values:
679 * @arg @ref LL_USART_WAKEUP_IDLELINE
680 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
682 __STATIC_INLINE
uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef
*USARTx
)
684 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_WAKE
));
688 * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits)
689 * @rmtoll CR1 M0 LL_USART_SetDataWidth\n
690 * CR1 M1 LL_USART_SetDataWidth
691 * @param USARTx USART Instance
692 * @param DataWidth This parameter can be one of the following values:
693 * @arg @ref LL_USART_DATAWIDTH_7B
694 * @arg @ref LL_USART_DATAWIDTH_8B
695 * @arg @ref LL_USART_DATAWIDTH_9B
698 __STATIC_INLINE
void LL_USART_SetDataWidth(USART_TypeDef
*USARTx
, uint32_t DataWidth
)
700 MODIFY_REG(USARTx
->CR1
, USART_CR1_M
, DataWidth
);
704 * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits)
705 * @rmtoll CR1 M0 LL_USART_GetDataWidth\n
706 * CR1 M1 LL_USART_GetDataWidth
707 * @param USARTx USART Instance
708 * @retval Returned value can be one of the following values:
709 * @arg @ref LL_USART_DATAWIDTH_7B
710 * @arg @ref LL_USART_DATAWIDTH_8B
711 * @arg @ref LL_USART_DATAWIDTH_9B
713 __STATIC_INLINE
uint32_t LL_USART_GetDataWidth(USART_TypeDef
*USARTx
)
715 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_M
));
719 * @brief Allow switch between Mute Mode and Active mode
720 * @rmtoll CR1 MME LL_USART_EnableMuteMode
721 * @param USARTx USART Instance
724 __STATIC_INLINE
void LL_USART_EnableMuteMode(USART_TypeDef
*USARTx
)
726 SET_BIT(USARTx
->CR1
, USART_CR1_MME
);
730 * @brief Prevent Mute Mode use. Set Receiver in active mode permanently.
731 * @rmtoll CR1 MME LL_USART_DisableMuteMode
732 * @param USARTx USART Instance
735 __STATIC_INLINE
void LL_USART_DisableMuteMode(USART_TypeDef
*USARTx
)
737 CLEAR_BIT(USARTx
->CR1
, USART_CR1_MME
);
741 * @brief Indicate if switch between Mute Mode and Active mode is allowed
742 * @rmtoll CR1 MME LL_USART_IsEnabledMuteMode
743 * @param USARTx USART Instance
744 * @retval State of bit (1 or 0).
746 __STATIC_INLINE
uint32_t LL_USART_IsEnabledMuteMode(USART_TypeDef
*USARTx
)
748 return ((READ_BIT(USARTx
->CR1
, USART_CR1_MME
) == (USART_CR1_MME
)) ? 1UL : 0UL);
752 * @brief Set Oversampling to 8-bit or 16-bit mode
753 * @rmtoll CR1 OVER8 LL_USART_SetOverSampling
754 * @param USARTx USART Instance
755 * @param OverSampling This parameter can be one of the following values:
756 * @arg @ref LL_USART_OVERSAMPLING_16
757 * @arg @ref LL_USART_OVERSAMPLING_8
760 __STATIC_INLINE
void LL_USART_SetOverSampling(USART_TypeDef
*USARTx
, uint32_t OverSampling
)
762 MODIFY_REG(USARTx
->CR1
, USART_CR1_OVER8
, OverSampling
);
766 * @brief Return Oversampling mode
767 * @rmtoll CR1 OVER8 LL_USART_GetOverSampling
768 * @param USARTx USART Instance
769 * @retval Returned value can be one of the following values:
770 * @arg @ref LL_USART_OVERSAMPLING_16
771 * @arg @ref LL_USART_OVERSAMPLING_8
773 __STATIC_INLINE
uint32_t LL_USART_GetOverSampling(USART_TypeDef
*USARTx
)
775 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_OVER8
));
779 * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not
780 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
781 * Synchronous mode is supported by the USARTx instance.
782 * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput
783 * @param USARTx USART Instance
784 * @param LastBitClockPulse This parameter can be one of the following values:
785 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
786 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
789 __STATIC_INLINE
void LL_USART_SetLastClkPulseOutput(USART_TypeDef
*USARTx
, uint32_t LastBitClockPulse
)
791 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBCL
, LastBitClockPulse
);
795 * @brief Retrieve Clock pulse of the last data bit output configuration
796 * (Last bit Clock pulse output to the SCLK pin or not)
797 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
798 * Synchronous mode is supported by the USARTx instance.
799 * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput
800 * @param USARTx USART Instance
801 * @retval Returned value can be one of the following values:
802 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
803 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
805 __STATIC_INLINE
uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef
*USARTx
)
807 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBCL
));
811 * @brief Select the phase of the clock output on the SCLK pin in synchronous mode
812 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
813 * Synchronous mode is supported by the USARTx instance.
814 * @rmtoll CR2 CPHA LL_USART_SetClockPhase
815 * @param USARTx USART Instance
816 * @param ClockPhase This parameter can be one of the following values:
817 * @arg @ref LL_USART_PHASE_1EDGE
818 * @arg @ref LL_USART_PHASE_2EDGE
821 __STATIC_INLINE
void LL_USART_SetClockPhase(USART_TypeDef
*USARTx
, uint32_t ClockPhase
)
823 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
, ClockPhase
);
827 * @brief Return phase of the clock output on the SCLK pin in synchronous mode
828 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
829 * Synchronous mode is supported by the USARTx instance.
830 * @rmtoll CR2 CPHA LL_USART_GetClockPhase
831 * @param USARTx USART Instance
832 * @retval Returned value can be one of the following values:
833 * @arg @ref LL_USART_PHASE_1EDGE
834 * @arg @ref LL_USART_PHASE_2EDGE
836 __STATIC_INLINE
uint32_t LL_USART_GetClockPhase(USART_TypeDef
*USARTx
)
838 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPHA
));
842 * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode
843 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
844 * Synchronous mode is supported by the USARTx instance.
845 * @rmtoll CR2 CPOL LL_USART_SetClockPolarity
846 * @param USARTx USART Instance
847 * @param ClockPolarity This parameter can be one of the following values:
848 * @arg @ref LL_USART_POLARITY_LOW
849 * @arg @ref LL_USART_POLARITY_HIGH
852 __STATIC_INLINE
void LL_USART_SetClockPolarity(USART_TypeDef
*USARTx
, uint32_t ClockPolarity
)
854 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPOL
, ClockPolarity
);
858 * @brief Return polarity of the clock output on the SCLK pin in synchronous mode
859 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
860 * Synchronous mode is supported by the USARTx instance.
861 * @rmtoll CR2 CPOL LL_USART_GetClockPolarity
862 * @param USARTx USART Instance
863 * @retval Returned value can be one of the following values:
864 * @arg @ref LL_USART_POLARITY_LOW
865 * @arg @ref LL_USART_POLARITY_HIGH
867 __STATIC_INLINE
uint32_t LL_USART_GetClockPolarity(USART_TypeDef
*USARTx
)
869 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPOL
));
873 * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse)
874 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
875 * Synchronous mode is supported by the USARTx instance.
876 * @note Call of this function is equivalent to following function call sequence :
877 * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function
878 * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function
879 * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function
880 * @rmtoll CR2 CPHA LL_USART_ConfigClock\n
881 * CR2 CPOL LL_USART_ConfigClock\n
882 * CR2 LBCL LL_USART_ConfigClock
883 * @param USARTx USART Instance
884 * @param Phase This parameter can be one of the following values:
885 * @arg @ref LL_USART_PHASE_1EDGE
886 * @arg @ref LL_USART_PHASE_2EDGE
887 * @param Polarity This parameter can be one of the following values:
888 * @arg @ref LL_USART_POLARITY_LOW
889 * @arg @ref LL_USART_POLARITY_HIGH
890 * @param LBCPOutput This parameter can be one of the following values:
891 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
892 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
895 __STATIC_INLINE
void LL_USART_ConfigClock(USART_TypeDef
*USARTx
, uint32_t Phase
, uint32_t Polarity
, uint32_t LBCPOutput
)
897 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
| USART_CR2_CPOL
| USART_CR2_LBCL
, Phase
| Polarity
| LBCPOutput
);
901 * @brief Enable Clock output on SCLK pin
902 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
903 * Synchronous mode is supported by the USARTx instance.
904 * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput
905 * @param USARTx USART Instance
908 __STATIC_INLINE
void LL_USART_EnableSCLKOutput(USART_TypeDef
*USARTx
)
910 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
914 * @brief Disable Clock output on SCLK pin
915 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
916 * Synchronous mode is supported by the USARTx instance.
917 * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput
918 * @param USARTx USART Instance
921 __STATIC_INLINE
void LL_USART_DisableSCLKOutput(USART_TypeDef
*USARTx
)
923 CLEAR_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
927 * @brief Indicate if Clock output on SCLK pin is enabled
928 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
929 * Synchronous mode is supported by the USARTx instance.
930 * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput
931 * @param USARTx USART Instance
932 * @retval State of bit (1 or 0).
934 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef
*USARTx
)
936 return ((READ_BIT(USARTx
->CR2
, USART_CR2_CLKEN
) == (USART_CR2_CLKEN
)) ? 1UL : 0UL);
940 * @brief Set the length of the stop bits
941 * @rmtoll CR2 STOP LL_USART_SetStopBitsLength
942 * @param USARTx USART Instance
943 * @param StopBits This parameter can be one of the following values:
944 * @arg @ref LL_USART_STOPBITS_0_5
945 * @arg @ref LL_USART_STOPBITS_1
946 * @arg @ref LL_USART_STOPBITS_1_5
947 * @arg @ref LL_USART_STOPBITS_2
950 __STATIC_INLINE
void LL_USART_SetStopBitsLength(USART_TypeDef
*USARTx
, uint32_t StopBits
)
952 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
956 * @brief Retrieve the length of the stop bits
957 * @rmtoll CR2 STOP LL_USART_GetStopBitsLength
958 * @param USARTx USART Instance
959 * @retval Returned value can be one of the following values:
960 * @arg @ref LL_USART_STOPBITS_0_5
961 * @arg @ref LL_USART_STOPBITS_1
962 * @arg @ref LL_USART_STOPBITS_1_5
963 * @arg @ref LL_USART_STOPBITS_2
965 __STATIC_INLINE
uint32_t LL_USART_GetStopBitsLength(USART_TypeDef
*USARTx
)
967 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_STOP
));
971 * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits)
972 * @note Call of this function is equivalent to following function call sequence :
973 * - Data Width configuration using @ref LL_USART_SetDataWidth() function
974 * - Parity Control and mode configuration using @ref LL_USART_SetParity() function
975 * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function
976 * @rmtoll CR1 PS LL_USART_ConfigCharacter\n
977 * CR1 PCE LL_USART_ConfigCharacter\n
978 * CR1 M0 LL_USART_ConfigCharacter\n
979 * CR1 M1 LL_USART_ConfigCharacter\n
980 * CR2 STOP LL_USART_ConfigCharacter
981 * @param USARTx USART Instance
982 * @param DataWidth This parameter can be one of the following values:
983 * @arg @ref LL_USART_DATAWIDTH_7B
984 * @arg @ref LL_USART_DATAWIDTH_8B
985 * @arg @ref LL_USART_DATAWIDTH_9B
986 * @param Parity This parameter can be one of the following values:
987 * @arg @ref LL_USART_PARITY_NONE
988 * @arg @ref LL_USART_PARITY_EVEN
989 * @arg @ref LL_USART_PARITY_ODD
990 * @param StopBits This parameter can be one of the following values:
991 * @arg @ref LL_USART_STOPBITS_0_5
992 * @arg @ref LL_USART_STOPBITS_1
993 * @arg @ref LL_USART_STOPBITS_1_5
994 * @arg @ref LL_USART_STOPBITS_2
997 __STATIC_INLINE
void LL_USART_ConfigCharacter(USART_TypeDef
*USARTx
, uint32_t DataWidth
, uint32_t Parity
,
1000 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
| USART_CR1_M
, Parity
| DataWidth
);
1001 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
1005 * @brief Configure TX/RX pins swapping setting.
1006 * @rmtoll CR2 SWAP LL_USART_SetTXRXSwap
1007 * @param USARTx USART Instance
1008 * @param SwapConfig This parameter can be one of the following values:
1009 * @arg @ref LL_USART_TXRX_STANDARD
1010 * @arg @ref LL_USART_TXRX_SWAPPED
1013 __STATIC_INLINE
void LL_USART_SetTXRXSwap(USART_TypeDef
*USARTx
, uint32_t SwapConfig
)
1015 MODIFY_REG(USARTx
->CR2
, USART_CR2_SWAP
, SwapConfig
);
1019 * @brief Retrieve TX/RX pins swapping configuration.
1020 * @rmtoll CR2 SWAP LL_USART_GetTXRXSwap
1021 * @param USARTx USART Instance
1022 * @retval Returned value can be one of the following values:
1023 * @arg @ref LL_USART_TXRX_STANDARD
1024 * @arg @ref LL_USART_TXRX_SWAPPED
1026 __STATIC_INLINE
uint32_t LL_USART_GetTXRXSwap(USART_TypeDef
*USARTx
)
1028 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_SWAP
));
1032 * @brief Configure RX pin active level logic
1033 * @rmtoll CR2 RXINV LL_USART_SetRXPinLevel
1034 * @param USARTx USART Instance
1035 * @param PinInvMethod This parameter can be one of the following values:
1036 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1037 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1040 __STATIC_INLINE
void LL_USART_SetRXPinLevel(USART_TypeDef
*USARTx
, uint32_t PinInvMethod
)
1042 MODIFY_REG(USARTx
->CR2
, USART_CR2_RXINV
, PinInvMethod
);
1046 * @brief Retrieve RX pin active level logic configuration
1047 * @rmtoll CR2 RXINV LL_USART_GetRXPinLevel
1048 * @param USARTx USART Instance
1049 * @retval Returned value can be one of the following values:
1050 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1051 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1053 __STATIC_INLINE
uint32_t LL_USART_GetRXPinLevel(USART_TypeDef
*USARTx
)
1055 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_RXINV
));
1059 * @brief Configure TX pin active level logic
1060 * @rmtoll CR2 TXINV LL_USART_SetTXPinLevel
1061 * @param USARTx USART Instance
1062 * @param PinInvMethod This parameter can be one of the following values:
1063 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1064 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1067 __STATIC_INLINE
void LL_USART_SetTXPinLevel(USART_TypeDef
*USARTx
, uint32_t PinInvMethod
)
1069 MODIFY_REG(USARTx
->CR2
, USART_CR2_TXINV
, PinInvMethod
);
1073 * @brief Retrieve TX pin active level logic configuration
1074 * @rmtoll CR2 TXINV LL_USART_GetTXPinLevel
1075 * @param USARTx USART Instance
1076 * @retval Returned value can be one of the following values:
1077 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1078 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1080 __STATIC_INLINE
uint32_t LL_USART_GetTXPinLevel(USART_TypeDef
*USARTx
)
1082 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_TXINV
));
1086 * @brief Configure Binary data logic.
1087 * @note Allow to define how Logical data from the data register are send/received :
1088 * either in positive/direct logic (1=H, 0=L) or in negative/inverse logic (1=L, 0=H)
1089 * @rmtoll CR2 DATAINV LL_USART_SetBinaryDataLogic
1090 * @param USARTx USART Instance
1091 * @param DataLogic This parameter can be one of the following values:
1092 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1093 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1096 __STATIC_INLINE
void LL_USART_SetBinaryDataLogic(USART_TypeDef
*USARTx
, uint32_t DataLogic
)
1098 MODIFY_REG(USARTx
->CR2
, USART_CR2_DATAINV
, DataLogic
);
1102 * @brief Retrieve Binary data configuration
1103 * @rmtoll CR2 DATAINV LL_USART_GetBinaryDataLogic
1104 * @param USARTx USART Instance
1105 * @retval Returned value can be one of the following values:
1106 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1107 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1109 __STATIC_INLINE
uint32_t LL_USART_GetBinaryDataLogic(USART_TypeDef
*USARTx
)
1111 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_DATAINV
));
1115 * @brief Configure transfer bit order (either Less or Most Significant Bit First)
1116 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1117 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1118 * @rmtoll CR2 MSBFIRST LL_USART_SetTransferBitOrder
1119 * @param USARTx USART Instance
1120 * @param BitOrder This parameter can be one of the following values:
1121 * @arg @ref LL_USART_BITORDER_LSBFIRST
1122 * @arg @ref LL_USART_BITORDER_MSBFIRST
1125 __STATIC_INLINE
void LL_USART_SetTransferBitOrder(USART_TypeDef
*USARTx
, uint32_t BitOrder
)
1127 MODIFY_REG(USARTx
->CR2
, USART_CR2_MSBFIRST
, BitOrder
);
1131 * @brief Return transfer bit order (either Less or Most Significant Bit First)
1132 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1133 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1134 * @rmtoll CR2 MSBFIRST LL_USART_GetTransferBitOrder
1135 * @param USARTx USART Instance
1136 * @retval Returned value can be one of the following values:
1137 * @arg @ref LL_USART_BITORDER_LSBFIRST
1138 * @arg @ref LL_USART_BITORDER_MSBFIRST
1140 __STATIC_INLINE
uint32_t LL_USART_GetTransferBitOrder(USART_TypeDef
*USARTx
)
1142 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_MSBFIRST
));
1146 * @brief Enable Auto Baud-Rate Detection
1147 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1148 * Auto Baud Rate detection feature is supported by the USARTx instance.
1149 * @rmtoll CR2 ABREN LL_USART_EnableAutoBaudRate
1150 * @param USARTx USART Instance
1153 __STATIC_INLINE
void LL_USART_EnableAutoBaudRate(USART_TypeDef
*USARTx
)
1155 SET_BIT(USARTx
->CR2
, USART_CR2_ABREN
);
1159 * @brief Disable Auto Baud-Rate Detection
1160 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1161 * Auto Baud Rate detection feature is supported by the USARTx instance.
1162 * @rmtoll CR2 ABREN LL_USART_DisableAutoBaudRate
1163 * @param USARTx USART Instance
1166 __STATIC_INLINE
void LL_USART_DisableAutoBaudRate(USART_TypeDef
*USARTx
)
1168 CLEAR_BIT(USARTx
->CR2
, USART_CR2_ABREN
);
1172 * @brief Indicate if Auto Baud-Rate Detection mechanism is enabled
1173 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1174 * Auto Baud Rate detection feature is supported by the USARTx instance.
1175 * @rmtoll CR2 ABREN LL_USART_IsEnabledAutoBaud
1176 * @param USARTx USART Instance
1177 * @retval State of bit (1 or 0).
1179 __STATIC_INLINE
uint32_t LL_USART_IsEnabledAutoBaud(USART_TypeDef
*USARTx
)
1181 return ((READ_BIT(USARTx
->CR2
, USART_CR2_ABREN
) == (USART_CR2_ABREN
)) ? 1UL : 0UL);
1185 * @brief Set Auto Baud-Rate mode bits
1186 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1187 * Auto Baud Rate detection feature is supported by the USARTx instance.
1188 * @rmtoll CR2 ABRMODE LL_USART_SetAutoBaudRateMode
1189 * @param USARTx USART Instance
1190 * @param AutoBaudRateMode This parameter can be one of the following values:
1191 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1192 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1193 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1194 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1197 __STATIC_INLINE
void LL_USART_SetAutoBaudRateMode(USART_TypeDef
*USARTx
, uint32_t AutoBaudRateMode
)
1199 MODIFY_REG(USARTx
->CR2
, USART_CR2_ABRMODE
, AutoBaudRateMode
);
1203 * @brief Return Auto Baud-Rate mode
1204 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1205 * Auto Baud Rate detection feature is supported by the USARTx instance.
1206 * @rmtoll CR2 ABRMODE LL_USART_GetAutoBaudRateMode
1207 * @param USARTx USART Instance
1208 * @retval Returned value can be one of the following values:
1209 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1210 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1211 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1212 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1214 __STATIC_INLINE
uint32_t LL_USART_GetAutoBaudRateMode(USART_TypeDef
*USARTx
)
1216 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ABRMODE
));
1220 * @brief Enable Receiver Timeout
1221 * @rmtoll CR2 RTOEN LL_USART_EnableRxTimeout
1222 * @param USARTx USART Instance
1225 __STATIC_INLINE
void LL_USART_EnableRxTimeout(USART_TypeDef
*USARTx
)
1227 SET_BIT(USARTx
->CR2
, USART_CR2_RTOEN
);
1231 * @brief Disable Receiver Timeout
1232 * @rmtoll CR2 RTOEN LL_USART_DisableRxTimeout
1233 * @param USARTx USART Instance
1236 __STATIC_INLINE
void LL_USART_DisableRxTimeout(USART_TypeDef
*USARTx
)
1238 CLEAR_BIT(USARTx
->CR2
, USART_CR2_RTOEN
);
1242 * @brief Indicate if Receiver Timeout feature is enabled
1243 * @rmtoll CR2 RTOEN LL_USART_IsEnabledRxTimeout
1244 * @param USARTx USART Instance
1245 * @retval State of bit (1 or 0).
1247 __STATIC_INLINE
uint32_t LL_USART_IsEnabledRxTimeout(USART_TypeDef
*USARTx
)
1249 return ((READ_BIT(USARTx
->CR2
, USART_CR2_RTOEN
) == (USART_CR2_RTOEN
)) ? 1UL : 0UL);
1253 * @brief Set Address of the USART node.
1254 * @note This is used in multiprocessor communication during Mute mode or Stop mode,
1255 * for wake up with address mark detection.
1256 * @note 4bits address node is used when 4-bit Address Detection is selected in ADDM7.
1257 * (b7-b4 should be set to 0)
1258 * 8bits address node is used when 7-bit Address Detection is selected in ADDM7.
1259 * (This is used in multiprocessor communication during Mute mode or Stop mode,
1260 * for wake up with 7-bit address mark detection.
1261 * The MSB of the character sent by the transmitter should be equal to 1.
1262 * It may also be used for character detection during normal reception,
1263 * Mute mode inactive (for example, end of block detection in ModBus protocol).
1264 * In this case, the whole received character (8-bit) is compared to the ADD[7:0]
1265 * value and CMF flag is set on match)
1266 * @rmtoll CR2 ADD LL_USART_ConfigNodeAddress\n
1267 * CR2 ADDM7 LL_USART_ConfigNodeAddress
1268 * @param USARTx USART Instance
1269 * @param AddressLen This parameter can be one of the following values:
1270 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1271 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1272 * @param NodeAddress 4 or 7 bit Address of the USART node.
1275 __STATIC_INLINE
void LL_USART_ConfigNodeAddress(USART_TypeDef
*USARTx
, uint32_t AddressLen
, uint32_t NodeAddress
)
1277 MODIFY_REG(USARTx
->CR2
, USART_CR2_ADD
| USART_CR2_ADDM7
,
1278 (uint32_t)(AddressLen
| (NodeAddress
<< USART_CR2_ADD_Pos
)));
1282 * @brief Return 8 bit Address of the USART node as set in ADD field of CR2.
1283 * @note If 4-bit Address Detection is selected in ADDM7,
1284 * only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant)
1285 * If 7-bit Address Detection is selected in ADDM7,
1286 * only 8bits (b7-b0) of returned value are relevant (b31-b8 are not relevant)
1287 * @rmtoll CR2 ADD LL_USART_GetNodeAddress
1288 * @param USARTx USART Instance
1289 * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255)
1291 __STATIC_INLINE
uint32_t LL_USART_GetNodeAddress(USART_TypeDef
*USARTx
)
1293 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ADD
) >> USART_CR2_ADD_Pos
);
1297 * @brief Return Length of Node Address used in Address Detection mode (7-bit or 4-bit)
1298 * @rmtoll CR2 ADDM7 LL_USART_GetNodeAddressLen
1299 * @param USARTx USART Instance
1300 * @retval Returned value can be one of the following values:
1301 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1302 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1304 __STATIC_INLINE
uint32_t LL_USART_GetNodeAddressLen(USART_TypeDef
*USARTx
)
1306 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ADDM7
));
1310 * @brief Enable RTS HW Flow Control
1311 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1312 * Hardware Flow control feature is supported by the USARTx instance.
1313 * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl
1314 * @param USARTx USART Instance
1317 __STATIC_INLINE
void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1319 SET_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
1323 * @brief Disable RTS HW Flow Control
1324 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1325 * Hardware Flow control feature is supported by the USARTx instance.
1326 * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl
1327 * @param USARTx USART Instance
1330 __STATIC_INLINE
void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1332 CLEAR_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
1336 * @brief Enable CTS HW Flow Control
1337 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1338 * Hardware Flow control feature is supported by the USARTx instance.
1339 * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl
1340 * @param USARTx USART Instance
1343 __STATIC_INLINE
void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1345 SET_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
1349 * @brief Disable CTS HW Flow Control
1350 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1351 * Hardware Flow control feature is supported by the USARTx instance.
1352 * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl
1353 * @param USARTx USART Instance
1356 __STATIC_INLINE
void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1358 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
1362 * @brief Configure HW Flow Control mode (both CTS and RTS)
1363 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1364 * Hardware Flow control feature is supported by the USARTx instance.
1365 * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n
1366 * CR3 CTSE LL_USART_SetHWFlowCtrl
1367 * @param USARTx USART Instance
1368 * @param HardwareFlowControl This parameter can be one of the following values:
1369 * @arg @ref LL_USART_HWCONTROL_NONE
1370 * @arg @ref LL_USART_HWCONTROL_RTS
1371 * @arg @ref LL_USART_HWCONTROL_CTS
1372 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1375 __STATIC_INLINE
void LL_USART_SetHWFlowCtrl(USART_TypeDef
*USARTx
, uint32_t HardwareFlowControl
)
1377 MODIFY_REG(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
, HardwareFlowControl
);
1381 * @brief Return HW Flow Control configuration (both CTS and RTS)
1382 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1383 * Hardware Flow control feature is supported by the USARTx instance.
1384 * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n
1385 * CR3 CTSE LL_USART_GetHWFlowCtrl
1386 * @param USARTx USART Instance
1387 * @retval Returned value can be one of the following values:
1388 * @arg @ref LL_USART_HWCONTROL_NONE
1389 * @arg @ref LL_USART_HWCONTROL_RTS
1390 * @arg @ref LL_USART_HWCONTROL_CTS
1391 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1393 __STATIC_INLINE
uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef
*USARTx
)
1395 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
));
1399 * @brief Enable One bit sampling method
1400 * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp
1401 * @param USARTx USART Instance
1404 __STATIC_INLINE
void LL_USART_EnableOneBitSamp(USART_TypeDef
*USARTx
)
1406 SET_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1410 * @brief Disable One bit sampling method
1411 * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp
1412 * @param USARTx USART Instance
1415 __STATIC_INLINE
void LL_USART_DisableOneBitSamp(USART_TypeDef
*USARTx
)
1417 CLEAR_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1421 * @brief Indicate if One bit sampling method is enabled
1422 * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp
1423 * @param USARTx USART Instance
1424 * @retval State of bit (1 or 0).
1426 __STATIC_INLINE
uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef
*USARTx
)
1428 return ((READ_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
) == (USART_CR3_ONEBIT
)) ? 1UL : 0UL);
1432 * @brief Enable Overrun detection
1433 * @rmtoll CR3 OVRDIS LL_USART_EnableOverrunDetect
1434 * @param USARTx USART Instance
1437 __STATIC_INLINE
void LL_USART_EnableOverrunDetect(USART_TypeDef
*USARTx
)
1439 CLEAR_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
);
1443 * @brief Disable Overrun detection
1444 * @rmtoll CR3 OVRDIS LL_USART_DisableOverrunDetect
1445 * @param USARTx USART Instance
1448 __STATIC_INLINE
void LL_USART_DisableOverrunDetect(USART_TypeDef
*USARTx
)
1450 SET_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
);
1454 * @brief Indicate if Overrun detection is enabled
1455 * @rmtoll CR3 OVRDIS LL_USART_IsEnabledOverrunDetect
1456 * @param USARTx USART Instance
1457 * @retval State of bit (1 or 0).
1459 __STATIC_INLINE
uint32_t LL_USART_IsEnabledOverrunDetect(USART_TypeDef
*USARTx
)
1461 return ((READ_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
) != USART_CR3_OVRDIS
) ? 1UL : 0UL);
1465 * @brief Configure USART BRR register for achieving expected Baud Rate value.
1466 * @note Compute and set USARTDIV value in BRR Register (full BRR content)
1467 * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values
1468 * @note Peripheral clock and Baud rate values provided as function parameters should be valid
1469 * (Baud rate value != 0)
1470 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1471 * @rmtoll BRR BRR LL_USART_SetBaudRate
1472 * @param USARTx USART Instance
1473 * @param PeriphClk Peripheral Clock
1474 * @param OverSampling This parameter can be one of the following values:
1475 * @arg @ref LL_USART_OVERSAMPLING_16
1476 * @arg @ref LL_USART_OVERSAMPLING_8
1477 * @param BaudRate Baud Rate
1480 __STATIC_INLINE
void LL_USART_SetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t OverSampling
,
1483 register uint32_t usartdiv
;
1484 register uint32_t brrtemp
;
1486 if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1488 usartdiv
= (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk
, BaudRate
));
1489 brrtemp
= usartdiv
& 0xFFF0U
;
1490 brrtemp
|= (uint16_t)((usartdiv
& (uint16_t)0x000FU
) >> 1U);
1491 USARTx
->BRR
= brrtemp
;
1495 USARTx
->BRR
= (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk
, BaudRate
));
1500 * @brief Return current Baud Rate value, according to USARTDIV present in BRR register
1501 * (full BRR content), and to used Peripheral Clock and Oversampling mode values
1502 * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned.
1503 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1504 * @rmtoll BRR BRR LL_USART_GetBaudRate
1505 * @param USARTx USART Instance
1506 * @param PeriphClk Peripheral Clock
1507 * @param OverSampling This parameter can be one of the following values:
1508 * @arg @ref LL_USART_OVERSAMPLING_16
1509 * @arg @ref LL_USART_OVERSAMPLING_8
1512 __STATIC_INLINE
uint32_t LL_USART_GetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t OverSampling
)
1514 register uint32_t usartdiv
;
1515 register uint32_t brrresult
= 0x0U
;
1517 usartdiv
= USARTx
->BRR
;
1521 /* Do not perform a division by 0 */
1523 else if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1525 usartdiv
= (uint16_t)((usartdiv
& 0xFFF0U
) | ((usartdiv
& 0x0007U
) << 1U)) ;
1528 brrresult
= (PeriphClk
* 2U) / usartdiv
;
1533 if ((usartdiv
& 0xFFFFU
) != 0U)
1535 brrresult
= PeriphClk
/ usartdiv
;
1542 * @brief Set Receiver Time Out Value (expressed in nb of bits duration)
1543 * @rmtoll RTOR RTO LL_USART_SetRxTimeout
1544 * @param USARTx USART Instance
1545 * @param Timeout Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1548 __STATIC_INLINE
void LL_USART_SetRxTimeout(USART_TypeDef
*USARTx
, uint32_t Timeout
)
1550 MODIFY_REG(USARTx
->RTOR
, USART_RTOR_RTO
, Timeout
);
1554 * @brief Get Receiver Time Out Value (expressed in nb of bits duration)
1555 * @rmtoll RTOR RTO LL_USART_GetRxTimeout
1556 * @param USARTx USART Instance
1557 * @retval Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1559 __STATIC_INLINE
uint32_t LL_USART_GetRxTimeout(USART_TypeDef
*USARTx
)
1561 return (uint32_t)(READ_BIT(USARTx
->RTOR
, USART_RTOR_RTO
));
1565 * @brief Set Block Length value in reception
1566 * @rmtoll RTOR BLEN LL_USART_SetBlockLength
1567 * @param USARTx USART Instance
1568 * @param BlockLength Value between Min_Data=0x00 and Max_Data=0xFF
1571 __STATIC_INLINE
void LL_USART_SetBlockLength(USART_TypeDef
*USARTx
, uint32_t BlockLength
)
1573 MODIFY_REG(USARTx
->RTOR
, USART_RTOR_BLEN
, BlockLength
<< USART_RTOR_BLEN_Pos
);
1577 * @brief Get Block Length value in reception
1578 * @rmtoll RTOR BLEN LL_USART_GetBlockLength
1579 * @param USARTx USART Instance
1580 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1582 __STATIC_INLINE
uint32_t LL_USART_GetBlockLength(USART_TypeDef
*USARTx
)
1584 return (uint32_t)(READ_BIT(USARTx
->RTOR
, USART_RTOR_BLEN
) >> USART_RTOR_BLEN_Pos
);
1591 /** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature
1596 * @brief Enable IrDA mode
1597 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1598 * IrDA feature is supported by the USARTx instance.
1599 * @rmtoll CR3 IREN LL_USART_EnableIrda
1600 * @param USARTx USART Instance
1603 __STATIC_INLINE
void LL_USART_EnableIrda(USART_TypeDef
*USARTx
)
1605 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
1609 * @brief Disable IrDA mode
1610 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1611 * IrDA feature is supported by the USARTx instance.
1612 * @rmtoll CR3 IREN LL_USART_DisableIrda
1613 * @param USARTx USART Instance
1616 __STATIC_INLINE
void LL_USART_DisableIrda(USART_TypeDef
*USARTx
)
1618 CLEAR_BIT(USARTx
->CR3
, USART_CR3_IREN
);
1622 * @brief Indicate if IrDA mode is enabled
1623 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1624 * IrDA feature is supported by the USARTx instance.
1625 * @rmtoll CR3 IREN LL_USART_IsEnabledIrda
1626 * @param USARTx USART Instance
1627 * @retval State of bit (1 or 0).
1629 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIrda(USART_TypeDef
*USARTx
)
1631 return ((READ_BIT(USARTx
->CR3
, USART_CR3_IREN
) == (USART_CR3_IREN
)) ? 1UL : 0UL);
1635 * @brief Configure IrDA Power Mode (Normal or Low Power)
1636 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1637 * IrDA feature is supported by the USARTx instance.
1638 * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode
1639 * @param USARTx USART Instance
1640 * @param PowerMode This parameter can be one of the following values:
1641 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1642 * @arg @ref LL_USART_IRDA_POWER_LOW
1645 __STATIC_INLINE
void LL_USART_SetIrdaPowerMode(USART_TypeDef
*USARTx
, uint32_t PowerMode
)
1647 MODIFY_REG(USARTx
->CR3
, USART_CR3_IRLP
, PowerMode
);
1651 * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power)
1652 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1653 * IrDA feature is supported by the USARTx instance.
1654 * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode
1655 * @param USARTx USART Instance
1656 * @retval Returned value can be one of the following values:
1657 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1658 * @arg @ref LL_USART_PHASE_2EDGE
1660 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef
*USARTx
)
1662 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_IRLP
));
1666 * @brief Set Irda prescaler value, used for dividing the USART clock source
1667 * to achieve the Irda Low Power frequency (8 bits value)
1668 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1669 * IrDA feature is supported by the USARTx instance.
1670 * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler
1671 * @param USARTx USART Instance
1672 * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF
1675 __STATIC_INLINE
void LL_USART_SetIrdaPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
1677 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_PSC
, (uint16_t)PrescalerValue
);
1681 * @brief Return Irda prescaler value, used for dividing the USART clock source
1682 * to achieve the Irda Low Power frequency (8 bits value)
1683 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1684 * IrDA feature is supported by the USARTx instance.
1685 * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler
1686 * @param USARTx USART Instance
1687 * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF)
1689 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef
*USARTx
)
1691 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
1698 /** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature
1703 * @brief Enable Smartcard NACK transmission
1704 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1705 * Smartcard feature is supported by the USARTx instance.
1706 * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK
1707 * @param USARTx USART Instance
1710 __STATIC_INLINE
void LL_USART_EnableSmartcardNACK(USART_TypeDef
*USARTx
)
1712 SET_BIT(USARTx
->CR3
, USART_CR3_NACK
);
1716 * @brief Disable Smartcard NACK transmission
1717 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1718 * Smartcard feature is supported by the USARTx instance.
1719 * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK
1720 * @param USARTx USART Instance
1723 __STATIC_INLINE
void LL_USART_DisableSmartcardNACK(USART_TypeDef
*USARTx
)
1725 CLEAR_BIT(USARTx
->CR3
, USART_CR3_NACK
);
1729 * @brief Indicate if Smartcard NACK transmission is enabled
1730 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1731 * Smartcard feature is supported by the USARTx instance.
1732 * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK
1733 * @param USARTx USART Instance
1734 * @retval State of bit (1 or 0).
1736 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef
*USARTx
)
1738 return ((READ_BIT(USARTx
->CR3
, USART_CR3_NACK
) == (USART_CR3_NACK
)) ? 1UL : 0UL);
1742 * @brief Enable Smartcard mode
1743 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1744 * Smartcard feature is supported by the USARTx instance.
1745 * @rmtoll CR3 SCEN LL_USART_EnableSmartcard
1746 * @param USARTx USART Instance
1749 __STATIC_INLINE
void LL_USART_EnableSmartcard(USART_TypeDef
*USARTx
)
1751 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
1755 * @brief Disable Smartcard mode
1756 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1757 * Smartcard feature is supported by the USARTx instance.
1758 * @rmtoll CR3 SCEN LL_USART_DisableSmartcard
1759 * @param USARTx USART Instance
1762 __STATIC_INLINE
void LL_USART_DisableSmartcard(USART_TypeDef
*USARTx
)
1764 CLEAR_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
1768 * @brief Indicate if Smartcard mode is enabled
1769 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1770 * Smartcard feature is supported by the USARTx instance.
1771 * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard
1772 * @param USARTx USART Instance
1773 * @retval State of bit (1 or 0).
1775 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef
*USARTx
)
1777 return ((READ_BIT(USARTx
->CR3
, USART_CR3_SCEN
) == (USART_CR3_SCEN
)) ? 1UL : 0UL);
1781 * @brief Set Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1782 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1783 * Smartcard feature is supported by the USARTx instance.
1784 * @note This bit-field specifies the number of retries in transmit and receive, in Smartcard mode.
1785 * In transmission mode, it specifies the number of automatic retransmission retries, before
1786 * generating a transmission error (FE bit set).
1787 * In reception mode, it specifies the number or erroneous reception trials, before generating a
1788 * reception error (RXNE and PE bits set)
1789 * @rmtoll CR3 SCARCNT LL_USART_SetSmartcardAutoRetryCount
1790 * @param USARTx USART Instance
1791 * @param AutoRetryCount Value between Min_Data=0 and Max_Data=7
1794 __STATIC_INLINE
void LL_USART_SetSmartcardAutoRetryCount(USART_TypeDef
*USARTx
, uint32_t AutoRetryCount
)
1796 MODIFY_REG(USARTx
->CR3
, USART_CR3_SCARCNT
, AutoRetryCount
<< USART_CR3_SCARCNT_Pos
);
1800 * @brief Return Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1801 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1802 * Smartcard feature is supported by the USARTx instance.
1803 * @rmtoll CR3 SCARCNT LL_USART_GetSmartcardAutoRetryCount
1804 * @param USARTx USART Instance
1805 * @retval Smartcard Auto-Retry Count value (Value between Min_Data=0 and Max_Data=7)
1807 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardAutoRetryCount(USART_TypeDef
*USARTx
)
1809 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_SCARCNT
) >> USART_CR3_SCARCNT_Pos
);
1813 * @brief Set Smartcard prescaler value, used for dividing the USART clock
1814 * source to provide the SMARTCARD Clock (5 bits value)
1815 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1816 * Smartcard feature is supported by the USARTx instance.
1817 * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler
1818 * @param USARTx USART Instance
1819 * @param PrescalerValue Value between Min_Data=0 and Max_Data=31
1822 __STATIC_INLINE
void LL_USART_SetSmartcardPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
1824 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_PSC
, (uint16_t)PrescalerValue
);
1828 * @brief Return Smartcard prescaler value, used for dividing the USART clock
1829 * source to provide the SMARTCARD Clock (5 bits value)
1830 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1831 * Smartcard feature is supported by the USARTx instance.
1832 * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler
1833 * @param USARTx USART Instance
1834 * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31)
1836 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef
*USARTx
)
1838 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
1842 * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods
1843 * (GT[7:0] bits : Guard time value)
1844 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1845 * Smartcard feature is supported by the USARTx instance.
1846 * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime
1847 * @param USARTx USART Instance
1848 * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF
1851 __STATIC_INLINE
void LL_USART_SetSmartcardGuardTime(USART_TypeDef
*USARTx
, uint32_t GuardTime
)
1853 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_GT
, (uint16_t)(GuardTime
<< USART_GTPR_GT_Pos
));
1857 * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods
1858 * (GT[7:0] bits : Guard time value)
1859 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1860 * Smartcard feature is supported by the USARTx instance.
1861 * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime
1862 * @param USARTx USART Instance
1863 * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF)
1865 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef
*USARTx
)
1867 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_GT
) >> USART_GTPR_GT_Pos
);
1874 /** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature
1879 * @brief Enable Single Wire Half-Duplex mode
1880 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1881 * Half-Duplex mode is supported by the USARTx instance.
1882 * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex
1883 * @param USARTx USART Instance
1886 __STATIC_INLINE
void LL_USART_EnableHalfDuplex(USART_TypeDef
*USARTx
)
1888 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
1892 * @brief Disable Single Wire Half-Duplex mode
1893 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1894 * Half-Duplex mode is supported by the USARTx instance.
1895 * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex
1896 * @param USARTx USART Instance
1899 __STATIC_INLINE
void LL_USART_DisableHalfDuplex(USART_TypeDef
*USARTx
)
1901 CLEAR_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
1905 * @brief Indicate if Single Wire Half-Duplex mode is enabled
1906 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1907 * Half-Duplex mode is supported by the USARTx instance.
1908 * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex
1909 * @param USARTx USART Instance
1910 * @retval State of bit (1 or 0).
1912 __STATIC_INLINE
uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef
*USARTx
)
1914 return ((READ_BIT(USARTx
->CR3
, USART_CR3_HDSEL
) == (USART_CR3_HDSEL
)) ? 1UL : 0UL);
1921 /** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature
1926 * @brief Set LIN Break Detection Length
1927 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1928 * LIN feature is supported by the USARTx instance.
1929 * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen
1930 * @param USARTx USART Instance
1931 * @param LINBDLength This parameter can be one of the following values:
1932 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1933 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1936 __STATIC_INLINE
void LL_USART_SetLINBrkDetectionLen(USART_TypeDef
*USARTx
, uint32_t LINBDLength
)
1938 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBDL
, LINBDLength
);
1942 * @brief Return LIN Break Detection Length
1943 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1944 * LIN feature is supported by the USARTx instance.
1945 * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen
1946 * @param USARTx USART Instance
1947 * @retval Returned value can be one of the following values:
1948 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1949 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1951 __STATIC_INLINE
uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef
*USARTx
)
1953 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBDL
));
1957 * @brief Enable LIN mode
1958 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1959 * LIN feature is supported by the USARTx instance.
1960 * @rmtoll CR2 LINEN LL_USART_EnableLIN
1961 * @param USARTx USART Instance
1964 __STATIC_INLINE
void LL_USART_EnableLIN(USART_TypeDef
*USARTx
)
1966 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
1970 * @brief Disable LIN mode
1971 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1972 * LIN feature is supported by the USARTx instance.
1973 * @rmtoll CR2 LINEN LL_USART_DisableLIN
1974 * @param USARTx USART Instance
1977 __STATIC_INLINE
void LL_USART_DisableLIN(USART_TypeDef
*USARTx
)
1979 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
1983 * @brief Indicate if LIN mode is enabled
1984 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1985 * LIN feature is supported by the USARTx instance.
1986 * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN
1987 * @param USARTx USART Instance
1988 * @retval State of bit (1 or 0).
1990 __STATIC_INLINE
uint32_t LL_USART_IsEnabledLIN(USART_TypeDef
*USARTx
)
1992 return ((READ_BIT(USARTx
->CR2
, USART_CR2_LINEN
) == (USART_CR2_LINEN
)) ? 1UL : 0UL);
1999 /** @defgroup USART_LL_EF_Configuration_DE Configuration functions related to Driver Enable feature
2004 * @brief Set DEDT (Driver Enable De-Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2005 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2006 * Driver Enable feature is supported by the USARTx instance.
2007 * @rmtoll CR1 DEDT LL_USART_SetDEDeassertionTime
2008 * @param USARTx USART Instance
2009 * @param Time Value between Min_Data=0 and Max_Data=31
2012 __STATIC_INLINE
void LL_USART_SetDEDeassertionTime(USART_TypeDef
*USARTx
, uint32_t Time
)
2014 MODIFY_REG(USARTx
->CR1
, USART_CR1_DEDT
, Time
<< USART_CR1_DEDT_Pos
);
2018 * @brief Return DEDT (Driver Enable De-Assertion Time)
2019 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2020 * Driver Enable feature is supported by the USARTx instance.
2021 * @rmtoll CR1 DEDT LL_USART_GetDEDeassertionTime
2022 * @param USARTx USART Instance
2023 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2025 __STATIC_INLINE
uint32_t LL_USART_GetDEDeassertionTime(USART_TypeDef
*USARTx
)
2027 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_DEDT
) >> USART_CR1_DEDT_Pos
);
2031 * @brief Set DEAT (Driver Enable Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2032 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2033 * Driver Enable feature is supported by the USARTx instance.
2034 * @rmtoll CR1 DEAT LL_USART_SetDEAssertionTime
2035 * @param USARTx USART Instance
2036 * @param Time Value between Min_Data=0 and Max_Data=31
2039 __STATIC_INLINE
void LL_USART_SetDEAssertionTime(USART_TypeDef
*USARTx
, uint32_t Time
)
2041 MODIFY_REG(USARTx
->CR1
, USART_CR1_DEAT
, Time
<< USART_CR1_DEAT_Pos
);
2045 * @brief Return DEAT (Driver Enable Assertion Time)
2046 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2047 * Driver Enable feature is supported by the USARTx instance.
2048 * @rmtoll CR1 DEAT LL_USART_GetDEAssertionTime
2049 * @param USARTx USART Instance
2050 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2052 __STATIC_INLINE
uint32_t LL_USART_GetDEAssertionTime(USART_TypeDef
*USARTx
)
2054 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_DEAT
) >> USART_CR1_DEAT_Pos
);
2058 * @brief Enable Driver Enable (DE) Mode
2059 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2060 * Driver Enable feature is supported by the USARTx instance.
2061 * @rmtoll CR3 DEM LL_USART_EnableDEMode
2062 * @param USARTx USART Instance
2065 __STATIC_INLINE
void LL_USART_EnableDEMode(USART_TypeDef
*USARTx
)
2067 SET_BIT(USARTx
->CR3
, USART_CR3_DEM
);
2071 * @brief Disable Driver Enable (DE) Mode
2072 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2073 * Driver Enable feature is supported by the USARTx instance.
2074 * @rmtoll CR3 DEM LL_USART_DisableDEMode
2075 * @param USARTx USART Instance
2078 __STATIC_INLINE
void LL_USART_DisableDEMode(USART_TypeDef
*USARTx
)
2080 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DEM
);
2084 * @brief Indicate if Driver Enable (DE) Mode is enabled
2085 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2086 * Driver Enable feature is supported by the USARTx instance.
2087 * @rmtoll CR3 DEM LL_USART_IsEnabledDEMode
2088 * @param USARTx USART Instance
2089 * @retval State of bit (1 or 0).
2091 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDEMode(USART_TypeDef
*USARTx
)
2093 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DEM
) == (USART_CR3_DEM
)) ? 1UL : 0UL);
2097 * @brief Select Driver Enable Polarity
2098 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2099 * Driver Enable feature is supported by the USARTx instance.
2100 * @rmtoll CR3 DEP LL_USART_SetDESignalPolarity
2101 * @param USARTx USART Instance
2102 * @param Polarity This parameter can be one of the following values:
2103 * @arg @ref LL_USART_DE_POLARITY_HIGH
2104 * @arg @ref LL_USART_DE_POLARITY_LOW
2107 __STATIC_INLINE
void LL_USART_SetDESignalPolarity(USART_TypeDef
*USARTx
, uint32_t Polarity
)
2109 MODIFY_REG(USARTx
->CR3
, USART_CR3_DEP
, Polarity
);
2113 * @brief Return Driver Enable Polarity
2114 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2115 * Driver Enable feature is supported by the USARTx instance.
2116 * @rmtoll CR3 DEP LL_USART_GetDESignalPolarity
2117 * @param USARTx USART Instance
2118 * @retval Returned value can be one of the following values:
2119 * @arg @ref LL_USART_DE_POLARITY_HIGH
2120 * @arg @ref LL_USART_DE_POLARITY_LOW
2122 __STATIC_INLINE
uint32_t LL_USART_GetDESignalPolarity(USART_TypeDef
*USARTx
)
2124 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_DEP
));
2131 /** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services
2136 * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART)
2137 * @note In UART mode, the following bits must be kept cleared:
2138 * - LINEN bit in the USART_CR2 register,
2139 * - CLKEN bit in the USART_CR2 register,
2140 * - SCEN bit in the USART_CR3 register,
2141 * - IREN bit in the USART_CR3 register,
2142 * - HDSEL bit in the USART_CR3 register.
2143 * @note Call of this function is equivalent to following function call sequence :
2144 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2145 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2146 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2147 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2148 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2149 * @note Other remaining configurations items related to Asynchronous Mode
2150 * (as Baud Rate, Word length, Parity, ...) should be set using
2151 * dedicated functions
2152 * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n
2153 * CR2 CLKEN LL_USART_ConfigAsyncMode\n
2154 * CR3 SCEN LL_USART_ConfigAsyncMode\n
2155 * CR3 IREN LL_USART_ConfigAsyncMode\n
2156 * CR3 HDSEL LL_USART_ConfigAsyncMode
2157 * @param USARTx USART Instance
2160 __STATIC_INLINE
void LL_USART_ConfigAsyncMode(USART_TypeDef
*USARTx
)
2162 /* In Asynchronous mode, the following bits must be kept cleared:
2163 - LINEN, CLKEN bits in the USART_CR2 register,
2164 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2165 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2166 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
2170 * @brief Perform basic configuration of USART for enabling use in Synchronous Mode
2171 * @note In Synchronous mode, the following bits must be kept cleared:
2172 * - LINEN bit in the USART_CR2 register,
2173 * - SCEN bit in the USART_CR3 register,
2174 * - IREN bit in the USART_CR3 register,
2175 * - HDSEL bit in the USART_CR3 register.
2176 * This function also sets the USART in Synchronous mode.
2177 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
2178 * Synchronous mode is supported by the USARTx instance.
2179 * @note Call of this function is equivalent to following function call sequence :
2180 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2181 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2182 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2183 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2184 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2185 * @note Other remaining configurations items related to Synchronous Mode
2186 * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using
2187 * dedicated functions
2188 * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n
2189 * CR2 CLKEN LL_USART_ConfigSyncMode\n
2190 * CR3 SCEN LL_USART_ConfigSyncMode\n
2191 * CR3 IREN LL_USART_ConfigSyncMode\n
2192 * CR3 HDSEL LL_USART_ConfigSyncMode
2193 * @param USARTx USART Instance
2196 __STATIC_INLINE
void LL_USART_ConfigSyncMode(USART_TypeDef
*USARTx
)
2198 /* In Synchronous mode, the following bits must be kept cleared:
2199 - LINEN bit in the USART_CR2 register,
2200 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2201 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
2202 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
2203 /* set the UART/USART in Synchronous mode */
2204 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
2208 * @brief Perform basic configuration of USART for enabling use in LIN Mode
2209 * @note In LIN mode, the following bits must be kept cleared:
2210 * - STOP and CLKEN bits in the USART_CR2 register,
2211 * - SCEN bit in the USART_CR3 register,
2212 * - IREN bit in the USART_CR3 register,
2213 * - HDSEL bit in the USART_CR3 register.
2214 * This function also set the UART/USART in LIN mode.
2215 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2216 * LIN feature is supported by the USARTx instance.
2217 * @note Call of this function is equivalent to following function call sequence :
2218 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2219 * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2220 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2221 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2222 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2223 * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function
2224 * @note Other remaining configurations items related to LIN Mode
2225 * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using
2226 * dedicated functions
2227 * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n
2228 * CR2 STOP LL_USART_ConfigLINMode\n
2229 * CR2 LINEN LL_USART_ConfigLINMode\n
2230 * CR3 IREN LL_USART_ConfigLINMode\n
2231 * CR3 SCEN LL_USART_ConfigLINMode\n
2232 * CR3 HDSEL LL_USART_ConfigLINMode
2233 * @param USARTx USART Instance
2236 __STATIC_INLINE
void LL_USART_ConfigLINMode(USART_TypeDef
*USARTx
)
2238 /* In LIN mode, the following bits must be kept cleared:
2239 - STOP and CLKEN bits in the USART_CR2 register,
2240 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2241 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_CLKEN
| USART_CR2_STOP
));
2242 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_SCEN
| USART_CR3_HDSEL
));
2243 /* Set the UART/USART in LIN mode */
2244 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
2248 * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode
2249 * @note In Half Duplex mode, the following bits must be kept cleared:
2250 * - LINEN bit in the USART_CR2 register,
2251 * - CLKEN bit in the USART_CR2 register,
2252 * - SCEN bit in the USART_CR3 register,
2253 * - IREN bit in the USART_CR3 register,
2254 * This function also sets the UART/USART in Half Duplex mode.
2255 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2256 * Half-Duplex mode is supported by the USARTx instance.
2257 * @note Call of this function is equivalent to following function call sequence :
2258 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2259 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2260 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2261 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2262 * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function
2263 * @note Other remaining configurations items related to Half Duplex Mode
2264 * (as Baud Rate, Word length, Parity, ...) should be set using
2265 * dedicated functions
2266 * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n
2267 * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n
2268 * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n
2269 * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n
2270 * CR3 IREN LL_USART_ConfigHalfDuplexMode
2271 * @param USARTx USART Instance
2274 __STATIC_INLINE
void LL_USART_ConfigHalfDuplexMode(USART_TypeDef
*USARTx
)
2276 /* In Half Duplex mode, the following bits must be kept cleared:
2277 - LINEN and CLKEN bits in the USART_CR2 register,
2278 - SCEN and IREN bits in the USART_CR3 register.*/
2279 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2280 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
));
2281 /* set the UART/USART in Half Duplex mode */
2282 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
2286 * @brief Perform basic configuration of USART for enabling use in Smartcard Mode
2287 * @note In Smartcard mode, the following bits must be kept cleared:
2288 * - LINEN bit in the USART_CR2 register,
2289 * - IREN bit in the USART_CR3 register,
2290 * - HDSEL bit in the USART_CR3 register.
2291 * This function also configures Stop bits to 1.5 bits and
2292 * sets the USART in Smartcard mode (SCEN bit).
2293 * Clock Output is also enabled (CLKEN).
2294 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2295 * Smartcard feature is supported by the USARTx instance.
2296 * @note Call of this function is equivalent to following function call sequence :
2297 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2298 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2299 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2300 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2301 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2302 * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function
2303 * @note Other remaining configurations items related to Smartcard Mode
2304 * (as Baud Rate, Word length, Parity, ...) should be set using
2305 * dedicated functions
2306 * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n
2307 * CR2 STOP LL_USART_ConfigSmartcardMode\n
2308 * CR2 CLKEN LL_USART_ConfigSmartcardMode\n
2309 * CR3 HDSEL LL_USART_ConfigSmartcardMode\n
2310 * CR3 SCEN LL_USART_ConfigSmartcardMode
2311 * @param USARTx USART Instance
2314 __STATIC_INLINE
void LL_USART_ConfigSmartcardMode(USART_TypeDef
*USARTx
)
2316 /* In Smartcard mode, the following bits must be kept cleared:
2317 - LINEN bit in the USART_CR2 register,
2318 - IREN and HDSEL bits in the USART_CR3 register.*/
2319 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
2320 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_HDSEL
));
2321 /* Configure Stop bits to 1.5 bits */
2322 /* Synchronous mode is activated by default */
2323 SET_BIT(USARTx
->CR2
, (USART_CR2_STOP_0
| USART_CR2_STOP_1
| USART_CR2_CLKEN
));
2324 /* set the UART/USART in Smartcard mode */
2325 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
2329 * @brief Perform basic configuration of USART for enabling use in Irda Mode
2330 * @note In IRDA mode, the following bits must be kept cleared:
2331 * - LINEN bit in the USART_CR2 register,
2332 * - STOP and CLKEN bits in the USART_CR2 register,
2333 * - SCEN bit in the USART_CR3 register,
2334 * - HDSEL bit in the USART_CR3 register.
2335 * This function also sets the UART/USART in IRDA mode (IREN bit).
2336 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2337 * IrDA feature is supported by the USARTx instance.
2338 * @note Call of this function is equivalent to following function call sequence :
2339 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2340 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2341 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2342 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2343 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2344 * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function
2345 * @note Other remaining configurations items related to Irda Mode
2346 * (as Baud Rate, Word length, Power mode, ...) should be set using
2347 * dedicated functions
2348 * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n
2349 * CR2 CLKEN LL_USART_ConfigIrdaMode\n
2350 * CR2 STOP LL_USART_ConfigIrdaMode\n
2351 * CR3 SCEN LL_USART_ConfigIrdaMode\n
2352 * CR3 HDSEL LL_USART_ConfigIrdaMode\n
2353 * CR3 IREN LL_USART_ConfigIrdaMode
2354 * @param USARTx USART Instance
2357 __STATIC_INLINE
void LL_USART_ConfigIrdaMode(USART_TypeDef
*USARTx
)
2359 /* In IRDA mode, the following bits must be kept cleared:
2360 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
2361 - SCEN and HDSEL bits in the USART_CR3 register.*/
2362 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
| USART_CR2_STOP
));
2363 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
));
2364 /* set the UART/USART in IRDA mode */
2365 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
2369 * @brief Perform basic configuration of USART for enabling use in Multi processor Mode
2370 * (several USARTs connected in a network, one of the USARTs can be the master,
2371 * its TX output connected to the RX inputs of the other slaves USARTs).
2372 * @note In MultiProcessor mode, the following bits must be kept cleared:
2373 * - LINEN bit in the USART_CR2 register,
2374 * - CLKEN bit in the USART_CR2 register,
2375 * - SCEN bit in the USART_CR3 register,
2376 * - IREN bit in the USART_CR3 register,
2377 * - HDSEL bit in the USART_CR3 register.
2378 * @note Call of this function is equivalent to following function call sequence :
2379 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2380 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2381 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2382 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2383 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2384 * @note Other remaining configurations items related to Multi processor Mode
2385 * (as Baud Rate, Wake Up Method, Node address, ...) should be set using
2386 * dedicated functions
2387 * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n
2388 * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n
2389 * CR3 SCEN LL_USART_ConfigMultiProcessMode\n
2390 * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n
2391 * CR3 IREN LL_USART_ConfigMultiProcessMode
2392 * @param USARTx USART Instance
2395 __STATIC_INLINE
void LL_USART_ConfigMultiProcessMode(USART_TypeDef
*USARTx
)
2397 /* In Multi Processor mode, the following bits must be kept cleared:
2398 - LINEN and CLKEN bits in the USART_CR2 register,
2399 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2400 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2401 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
| USART_CR3_IREN
));
2408 /** @defgroup USART_LL_EF_FLAG_Management FLAG_Management
2413 * @brief Check if the USART Parity Error Flag is set or not
2414 * @rmtoll ISR PE LL_USART_IsActiveFlag_PE
2415 * @param USARTx USART Instance
2416 * @retval State of bit (1 or 0).
2418 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef
*USARTx
)
2420 return ((READ_BIT(USARTx
->ISR
, USART_ISR_PE
) == (USART_ISR_PE
)) ? 1UL : 0UL);
2424 * @brief Check if the USART Framing Error Flag is set or not
2425 * @rmtoll ISR FE LL_USART_IsActiveFlag_FE
2426 * @param USARTx USART Instance
2427 * @retval State of bit (1 or 0).
2429 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef
*USARTx
)
2431 return ((READ_BIT(USARTx
->ISR
, USART_ISR_FE
) == (USART_ISR_FE
)) ? 1UL : 0UL);
2435 * @brief Check if the USART Noise error detected Flag is set or not
2436 * @rmtoll ISR NE LL_USART_IsActiveFlag_NE
2437 * @param USARTx USART Instance
2438 * @retval State of bit (1 or 0).
2440 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef
*USARTx
)
2442 return ((READ_BIT(USARTx
->ISR
, USART_ISR_NE
) == (USART_ISR_NE
)) ? 1UL : 0UL);
2446 * @brief Check if the USART OverRun Error Flag is set or not
2447 * @rmtoll ISR ORE LL_USART_IsActiveFlag_ORE
2448 * @param USARTx USART Instance
2449 * @retval State of bit (1 or 0).
2451 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef
*USARTx
)
2453 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ORE
) == (USART_ISR_ORE
)) ? 1UL : 0UL);
2457 * @brief Check if the USART IDLE line detected Flag is set or not
2458 * @rmtoll ISR IDLE LL_USART_IsActiveFlag_IDLE
2459 * @param USARTx USART Instance
2460 * @retval State of bit (1 or 0).
2462 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef
*USARTx
)
2464 return ((READ_BIT(USARTx
->ISR
, USART_ISR_IDLE
) == (USART_ISR_IDLE
)) ? 1UL : 0UL);
2468 * @brief Check if the USART Read Data Register Not Empty Flag is set or not
2469 * @rmtoll ISR RXNE LL_USART_IsActiveFlag_RXNE
2470 * @param USARTx USART Instance
2471 * @retval State of bit (1 or 0).
2473 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef
*USARTx
)
2475 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RXNE
) == (USART_ISR_RXNE
)) ? 1UL : 0UL);
2479 * @brief Check if the USART Transmission Complete Flag is set or not
2480 * @rmtoll ISR TC LL_USART_IsActiveFlag_TC
2481 * @param USARTx USART Instance
2482 * @retval State of bit (1 or 0).
2484 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef
*USARTx
)
2486 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TC
) == (USART_ISR_TC
)) ? 1UL : 0UL);
2490 * @brief Check if the USART Transmit Data Register Empty Flag is set or not
2491 * @rmtoll ISR TXE LL_USART_IsActiveFlag_TXE
2492 * @param USARTx USART Instance
2493 * @retval State of bit (1 or 0).
2495 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef
*USARTx
)
2497 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TXE
) == (USART_ISR_TXE
)) ? 1UL : 0UL);
2501 * @brief Check if the USART LIN Break Detection Flag is set or not
2502 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2503 * LIN feature is supported by the USARTx instance.
2504 * @rmtoll ISR LBDF LL_USART_IsActiveFlag_LBD
2505 * @param USARTx USART Instance
2506 * @retval State of bit (1 or 0).
2508 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef
*USARTx
)
2510 return ((READ_BIT(USARTx
->ISR
, USART_ISR_LBDF
) == (USART_ISR_LBDF
)) ? 1UL : 0UL);
2514 * @brief Check if the USART CTS interrupt Flag is set or not
2515 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2516 * Hardware Flow control feature is supported by the USARTx instance.
2517 * @rmtoll ISR CTSIF LL_USART_IsActiveFlag_nCTS
2518 * @param USARTx USART Instance
2519 * @retval State of bit (1 or 0).
2521 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef
*USARTx
)
2523 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CTSIF
) == (USART_ISR_CTSIF
)) ? 1UL : 0UL);
2527 * @brief Check if the USART CTS Flag is set or not
2528 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2529 * Hardware Flow control feature is supported by the USARTx instance.
2530 * @rmtoll ISR CTS LL_USART_IsActiveFlag_CTS
2531 * @param USARTx USART Instance
2532 * @retval State of bit (1 or 0).
2534 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_CTS(USART_TypeDef
*USARTx
)
2536 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CTS
) == (USART_ISR_CTS
)) ? 1UL : 0UL);
2540 * @brief Check if the USART Receiver Time Out Flag is set or not
2541 * @rmtoll ISR RTOF LL_USART_IsActiveFlag_RTO
2542 * @param USARTx USART Instance
2543 * @retval State of bit (1 or 0).
2545 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RTO(USART_TypeDef
*USARTx
)
2547 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RTOF
) == (USART_ISR_RTOF
)) ? 1UL : 0UL);
2551 * @brief Check if the USART End Of Block Flag is set or not
2552 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2553 * Smartcard feature is supported by the USARTx instance.
2554 * @rmtoll ISR EOBF LL_USART_IsActiveFlag_EOB
2555 * @param USARTx USART Instance
2556 * @retval State of bit (1 or 0).
2558 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_EOB(USART_TypeDef
*USARTx
)
2560 return ((READ_BIT(USARTx
->ISR
, USART_ISR_EOBF
) == (USART_ISR_EOBF
)) ? 1UL : 0UL);
2564 * @brief Check if the USART Auto-Baud Rate Error Flag is set or not
2565 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2566 * Auto Baud Rate detection feature is supported by the USARTx instance.
2567 * @rmtoll ISR ABRE LL_USART_IsActiveFlag_ABRE
2568 * @param USARTx USART Instance
2569 * @retval State of bit (1 or 0).
2571 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ABRE(USART_TypeDef
*USARTx
)
2573 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ABRE
) == (USART_ISR_ABRE
)) ? 1UL : 0UL);
2577 * @brief Check if the USART Auto-Baud Rate Flag is set or not
2578 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2579 * Auto Baud Rate detection feature is supported by the USARTx instance.
2580 * @rmtoll ISR ABRF LL_USART_IsActiveFlag_ABR
2581 * @param USARTx USART Instance
2582 * @retval State of bit (1 or 0).
2584 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ABR(USART_TypeDef
*USARTx
)
2586 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ABRF
) == (USART_ISR_ABRF
)) ? 1UL : 0UL);
2590 * @brief Check if the USART Busy Flag is set or not
2591 * @rmtoll ISR BUSY LL_USART_IsActiveFlag_BUSY
2592 * @param USARTx USART Instance
2593 * @retval State of bit (1 or 0).
2595 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_BUSY(USART_TypeDef
*USARTx
)
2597 return ((READ_BIT(USARTx
->ISR
, USART_ISR_BUSY
) == (USART_ISR_BUSY
)) ? 1UL : 0UL);
2601 * @brief Check if the USART Character Match Flag is set or not
2602 * @rmtoll ISR CMF LL_USART_IsActiveFlag_CM
2603 * @param USARTx USART Instance
2604 * @retval State of bit (1 or 0).
2606 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_CM(USART_TypeDef
*USARTx
)
2608 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CMF
) == (USART_ISR_CMF
)) ? 1UL : 0UL);
2612 * @brief Check if the USART Send Break Flag is set or not
2613 * @rmtoll ISR SBKF LL_USART_IsActiveFlag_SBK
2614 * @param USARTx USART Instance
2615 * @retval State of bit (1 or 0).
2617 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef
*USARTx
)
2619 return ((READ_BIT(USARTx
->ISR
, USART_ISR_SBKF
) == (USART_ISR_SBKF
)) ? 1UL : 0UL);
2623 * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not
2624 * @rmtoll ISR RWU LL_USART_IsActiveFlag_RWU
2625 * @param USARTx USART Instance
2626 * @retval State of bit (1 or 0).
2628 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef
*USARTx
)
2630 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RWU
) == (USART_ISR_RWU
)) ? 1UL : 0UL);
2634 * @brief Check if the USART Transmit Enable Acknowledge Flag is set or not
2635 * @rmtoll ISR TEACK LL_USART_IsActiveFlag_TEACK
2636 * @param USARTx USART Instance
2637 * @retval State of bit (1 or 0).
2639 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TEACK(USART_TypeDef
*USARTx
)
2641 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TEACK
) == (USART_ISR_TEACK
)) ? 1UL : 0UL);
2644 #if defined(USART_TCBGT_SUPPORT)
2645 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2647 * @brief Check if the Smartcard Transmission Complete Before Guard Time Flag is set or not
2648 * @rmtoll ISR TCBGT LL_USART_IsActiveFlag_TCBGT
2649 * @param USARTx USART Instance
2650 * @retval State of bit (1 or 0).
2652 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TCBGT(USART_TypeDef
*USARTx
)
2654 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TCBGT
) == (USART_ISR_TCBGT
)) ? 1UL : 0UL);
2659 * @brief Clear Parity Error Flag
2660 * @rmtoll ICR PECF LL_USART_ClearFlag_PE
2661 * @param USARTx USART Instance
2664 __STATIC_INLINE
void LL_USART_ClearFlag_PE(USART_TypeDef
*USARTx
)
2666 WRITE_REG(USARTx
->ICR
, USART_ICR_PECF
);
2670 * @brief Clear Framing Error Flag
2671 * @rmtoll ICR FECF LL_USART_ClearFlag_FE
2672 * @param USARTx USART Instance
2675 __STATIC_INLINE
void LL_USART_ClearFlag_FE(USART_TypeDef
*USARTx
)
2677 WRITE_REG(USARTx
->ICR
, USART_ICR_FECF
);
2681 * @brief Clear Noise Error detected Flag
2682 * @rmtoll ICR NCF LL_USART_ClearFlag_NE
2683 * @param USARTx USART Instance
2686 __STATIC_INLINE
void LL_USART_ClearFlag_NE(USART_TypeDef
*USARTx
)
2688 WRITE_REG(USARTx
->ICR
, USART_ICR_NCF
);
2692 * @brief Clear OverRun Error Flag
2693 * @rmtoll ICR ORECF LL_USART_ClearFlag_ORE
2694 * @param USARTx USART Instance
2697 __STATIC_INLINE
void LL_USART_ClearFlag_ORE(USART_TypeDef
*USARTx
)
2699 WRITE_REG(USARTx
->ICR
, USART_ICR_ORECF
);
2703 * @brief Clear IDLE line detected Flag
2704 * @rmtoll ICR IDLECF LL_USART_ClearFlag_IDLE
2705 * @param USARTx USART Instance
2708 __STATIC_INLINE
void LL_USART_ClearFlag_IDLE(USART_TypeDef
*USARTx
)
2710 WRITE_REG(USARTx
->ICR
, USART_ICR_IDLECF
);
2714 * @brief Clear Transmission Complete Flag
2715 * @rmtoll ICR TCCF LL_USART_ClearFlag_TC
2716 * @param USARTx USART Instance
2719 __STATIC_INLINE
void LL_USART_ClearFlag_TC(USART_TypeDef
*USARTx
)
2721 WRITE_REG(USARTx
->ICR
, USART_ICR_TCCF
);
2724 #if defined(USART_TCBGT_SUPPORT)
2725 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2727 * @brief Clear Smartcard Transmission Complete Before Guard Time Flag
2728 * @rmtoll ICR TCBGTCF LL_USART_ClearFlag_TCBGT
2729 * @param USARTx USART Instance
2732 __STATIC_INLINE
void LL_USART_ClearFlag_TCBGT(USART_TypeDef
*USARTx
)
2734 WRITE_REG(USARTx
->ICR
, USART_ICR_TCBGTCF
);
2739 * @brief Clear LIN Break Detection Flag
2740 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2741 * LIN feature is supported by the USARTx instance.
2742 * @rmtoll ICR LBDCF LL_USART_ClearFlag_LBD
2743 * @param USARTx USART Instance
2746 __STATIC_INLINE
void LL_USART_ClearFlag_LBD(USART_TypeDef
*USARTx
)
2748 WRITE_REG(USARTx
->ICR
, USART_ICR_LBDCF
);
2752 * @brief Clear CTS Interrupt Flag
2753 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2754 * Hardware Flow control feature is supported by the USARTx instance.
2755 * @rmtoll ICR CTSCF LL_USART_ClearFlag_nCTS
2756 * @param USARTx USART Instance
2759 __STATIC_INLINE
void LL_USART_ClearFlag_nCTS(USART_TypeDef
*USARTx
)
2761 WRITE_REG(USARTx
->ICR
, USART_ICR_CTSCF
);
2765 * @brief Clear Receiver Time Out Flag
2766 * @rmtoll ICR RTOCF LL_USART_ClearFlag_RTO
2767 * @param USARTx USART Instance
2770 __STATIC_INLINE
void LL_USART_ClearFlag_RTO(USART_TypeDef
*USARTx
)
2772 WRITE_REG(USARTx
->ICR
, USART_ICR_RTOCF
);
2776 * @brief Clear End Of Block Flag
2777 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2778 * Smartcard feature is supported by the USARTx instance.
2779 * @rmtoll ICR EOBCF LL_USART_ClearFlag_EOB
2780 * @param USARTx USART Instance
2783 __STATIC_INLINE
void LL_USART_ClearFlag_EOB(USART_TypeDef
*USARTx
)
2785 WRITE_REG(USARTx
->ICR
, USART_ICR_EOBCF
);
2789 * @brief Clear Character Match Flag
2790 * @rmtoll ICR CMCF LL_USART_ClearFlag_CM
2791 * @param USARTx USART Instance
2794 __STATIC_INLINE
void LL_USART_ClearFlag_CM(USART_TypeDef
*USARTx
)
2796 WRITE_REG(USARTx
->ICR
, USART_ICR_CMCF
);
2803 /** @defgroup USART_LL_EF_IT_Management IT_Management
2808 * @brief Enable IDLE Interrupt
2809 * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE
2810 * @param USARTx USART Instance
2813 __STATIC_INLINE
void LL_USART_EnableIT_IDLE(USART_TypeDef
*USARTx
)
2815 SET_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
2819 * @brief Enable RX Not Empty Interrupt
2820 * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE
2821 * @param USARTx USART Instance
2824 __STATIC_INLINE
void LL_USART_EnableIT_RXNE(USART_TypeDef
*USARTx
)
2826 SET_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
);
2830 * @brief Enable Transmission Complete Interrupt
2831 * @rmtoll CR1 TCIE LL_USART_EnableIT_TC
2832 * @param USARTx USART Instance
2835 __STATIC_INLINE
void LL_USART_EnableIT_TC(USART_TypeDef
*USARTx
)
2837 SET_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
2841 * @brief Enable TX Empty Interrupt
2842 * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE
2843 * @param USARTx USART Instance
2846 __STATIC_INLINE
void LL_USART_EnableIT_TXE(USART_TypeDef
*USARTx
)
2848 SET_BIT(USARTx
->CR1
, USART_CR1_TXEIE
);
2852 * @brief Enable Parity Error Interrupt
2853 * @rmtoll CR1 PEIE LL_USART_EnableIT_PE
2854 * @param USARTx USART Instance
2857 __STATIC_INLINE
void LL_USART_EnableIT_PE(USART_TypeDef
*USARTx
)
2859 SET_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
2863 * @brief Enable Character Match Interrupt
2864 * @rmtoll CR1 CMIE LL_USART_EnableIT_CM
2865 * @param USARTx USART Instance
2868 __STATIC_INLINE
void LL_USART_EnableIT_CM(USART_TypeDef
*USARTx
)
2870 SET_BIT(USARTx
->CR1
, USART_CR1_CMIE
);
2874 * @brief Enable Receiver Timeout Interrupt
2875 * @rmtoll CR1 RTOIE LL_USART_EnableIT_RTO
2876 * @param USARTx USART Instance
2879 __STATIC_INLINE
void LL_USART_EnableIT_RTO(USART_TypeDef
*USARTx
)
2881 SET_BIT(USARTx
->CR1
, USART_CR1_RTOIE
);
2885 * @brief Enable End Of Block Interrupt
2886 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2887 * Smartcard feature is supported by the USARTx instance.
2888 * @rmtoll CR1 EOBIE LL_USART_EnableIT_EOB
2889 * @param USARTx USART Instance
2892 __STATIC_INLINE
void LL_USART_EnableIT_EOB(USART_TypeDef
*USARTx
)
2894 SET_BIT(USARTx
->CR1
, USART_CR1_EOBIE
);
2898 * @brief Enable LIN Break Detection Interrupt
2899 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2900 * LIN feature is supported by the USARTx instance.
2901 * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD
2902 * @param USARTx USART Instance
2905 __STATIC_INLINE
void LL_USART_EnableIT_LBD(USART_TypeDef
*USARTx
)
2907 SET_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
2911 * @brief Enable Error Interrupt
2912 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
2913 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
2914 * 0: Interrupt is inhibited
2915 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
2916 * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR
2917 * @param USARTx USART Instance
2920 __STATIC_INLINE
void LL_USART_EnableIT_ERROR(USART_TypeDef
*USARTx
)
2922 SET_BIT(USARTx
->CR3
, USART_CR3_EIE
);
2926 * @brief Enable CTS Interrupt
2927 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2928 * Hardware Flow control feature is supported by the USARTx instance.
2929 * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS
2930 * @param USARTx USART Instance
2933 __STATIC_INLINE
void LL_USART_EnableIT_CTS(USART_TypeDef
*USARTx
)
2935 SET_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
2938 #if defined(USART_TCBGT_SUPPORT)
2939 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2941 * @brief Enable Smartcard Transmission Complete Before Guard Time Interrupt
2942 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2943 * Smartcard feature is supported by the USARTx instance.
2944 * @rmtoll CR3 TCBGTIE LL_USART_EnableIT_TCBGT
2945 * @param USARTx USART Instance
2948 __STATIC_INLINE
void LL_USART_EnableIT_TCBGT(USART_TypeDef
*USARTx
)
2950 SET_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
);
2955 * @brief Disable IDLE Interrupt
2956 * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE
2957 * @param USARTx USART Instance
2960 __STATIC_INLINE
void LL_USART_DisableIT_IDLE(USART_TypeDef
*USARTx
)
2962 CLEAR_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
2966 * @brief Disable RX Not Empty Interrupt
2967 * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE
2968 * @param USARTx USART Instance
2971 __STATIC_INLINE
void LL_USART_DisableIT_RXNE(USART_TypeDef
*USARTx
)
2973 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
);
2977 * @brief Disable Transmission Complete Interrupt
2978 * @rmtoll CR1 TCIE LL_USART_DisableIT_TC
2979 * @param USARTx USART Instance
2982 __STATIC_INLINE
void LL_USART_DisableIT_TC(USART_TypeDef
*USARTx
)
2984 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
2988 * @brief Disable TX Empty Interrupt
2989 * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE
2990 * @param USARTx USART Instance
2993 __STATIC_INLINE
void LL_USART_DisableIT_TXE(USART_TypeDef
*USARTx
)
2995 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TXEIE
);
2999 * @brief Disable Parity Error Interrupt
3000 * @rmtoll CR1 PEIE LL_USART_DisableIT_PE
3001 * @param USARTx USART Instance
3004 __STATIC_INLINE
void LL_USART_DisableIT_PE(USART_TypeDef
*USARTx
)
3006 CLEAR_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
3010 * @brief Disable Character Match Interrupt
3011 * @rmtoll CR1 CMIE LL_USART_DisableIT_CM
3012 * @param USARTx USART Instance
3015 __STATIC_INLINE
void LL_USART_DisableIT_CM(USART_TypeDef
*USARTx
)
3017 CLEAR_BIT(USARTx
->CR1
, USART_CR1_CMIE
);
3021 * @brief Disable Receiver Timeout Interrupt
3022 * @rmtoll CR1 RTOIE LL_USART_DisableIT_RTO
3023 * @param USARTx USART Instance
3026 __STATIC_INLINE
void LL_USART_DisableIT_RTO(USART_TypeDef
*USARTx
)
3028 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RTOIE
);
3032 * @brief Disable End Of Block Interrupt
3033 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3034 * Smartcard feature is supported by the USARTx instance.
3035 * @rmtoll CR1 EOBIE LL_USART_DisableIT_EOB
3036 * @param USARTx USART Instance
3039 __STATIC_INLINE
void LL_USART_DisableIT_EOB(USART_TypeDef
*USARTx
)
3041 CLEAR_BIT(USARTx
->CR1
, USART_CR1_EOBIE
);
3045 * @brief Disable LIN Break Detection Interrupt
3046 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3047 * LIN feature is supported by the USARTx instance.
3048 * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD
3049 * @param USARTx USART Instance
3052 __STATIC_INLINE
void LL_USART_DisableIT_LBD(USART_TypeDef
*USARTx
)
3054 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
3058 * @brief Disable Error Interrupt
3059 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3060 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3061 * 0: Interrupt is inhibited
3062 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3063 * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR
3064 * @param USARTx USART Instance
3067 __STATIC_INLINE
void LL_USART_DisableIT_ERROR(USART_TypeDef
*USARTx
)
3069 CLEAR_BIT(USARTx
->CR3
, USART_CR3_EIE
);
3073 * @brief Disable CTS Interrupt
3074 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3075 * Hardware Flow control feature is supported by the USARTx instance.
3076 * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS
3077 * @param USARTx USART Instance
3080 __STATIC_INLINE
void LL_USART_DisableIT_CTS(USART_TypeDef
*USARTx
)
3082 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
3085 #if defined(USART_TCBGT_SUPPORT)
3086 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
3088 * @brief Disable Smartcard Transmission Complete Before Guard Time Interrupt
3089 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3090 * Smartcard feature is supported by the USARTx instance.
3091 * @rmtoll CR3 TCBGTIE LL_USART_DisableIT_TCBGT
3092 * @param USARTx USART Instance
3095 __STATIC_INLINE
void LL_USART_DisableIT_TCBGT(USART_TypeDef
*USARTx
)
3097 CLEAR_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
);
3102 * @brief Check if the USART IDLE Interrupt source is enabled or disabled.
3103 * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE
3104 * @param USARTx USART Instance
3105 * @retval State of bit (1 or 0).
3107 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef
*USARTx
)
3109 return ((READ_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
) == (USART_CR1_IDLEIE
)) ? 1UL : 0UL);
3113 * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled.
3114 * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE
3115 * @param USARTx USART Instance
3116 * @retval State of bit (1 or 0).
3118 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef
*USARTx
)
3120 return ((READ_BIT(USARTx
->CR1
, USART_CR1_RXNEIE
) == (USART_CR1_RXNEIE
)) ? 1U : 0U);
3124 * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled.
3125 * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC
3126 * @param USARTx USART Instance
3127 * @retval State of bit (1 or 0).
3129 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef
*USARTx
)
3131 return ((READ_BIT(USARTx
->CR1
, USART_CR1_TCIE
) == (USART_CR1_TCIE
)) ? 1UL : 0UL);
3135 * @brief Check if the USART TX Empty Interrupt is enabled or disabled.
3136 * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE
3137 * @param USARTx USART Instance
3138 * @retval State of bit (1 or 0).
3140 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef
*USARTx
)
3142 return ((READ_BIT(USARTx
->CR1
, USART_CR1_TXEIE
) == (USART_CR1_TXEIE
)) ? 1U : 0U);
3146 * @brief Check if the USART Parity Error Interrupt is enabled or disabled.
3147 * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE
3148 * @param USARTx USART Instance
3149 * @retval State of bit (1 or 0).
3151 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef
*USARTx
)
3153 return ((READ_BIT(USARTx
->CR1
, USART_CR1_PEIE
) == (USART_CR1_PEIE
)) ? 1UL : 0UL);
3157 * @brief Check if the USART Character Match Interrupt is enabled or disabled.
3158 * @rmtoll CR1 CMIE LL_USART_IsEnabledIT_CM
3159 * @param USARTx USART Instance
3160 * @retval State of bit (1 or 0).
3162 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_CM(USART_TypeDef
*USARTx
)
3164 return ((READ_BIT(USARTx
->CR1
, USART_CR1_CMIE
) == (USART_CR1_CMIE
)) ? 1UL : 0UL);
3168 * @brief Check if the USART Receiver Timeout Interrupt is enabled or disabled.
3169 * @rmtoll CR1 RTOIE LL_USART_IsEnabledIT_RTO
3170 * @param USARTx USART Instance
3171 * @retval State of bit (1 or 0).
3173 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RTO(USART_TypeDef
*USARTx
)
3175 return ((READ_BIT(USARTx
->CR1
, USART_CR1_RTOIE
) == (USART_CR1_RTOIE
)) ? 1UL : 0UL);
3179 * @brief Check if the USART End Of Block Interrupt is enabled or disabled.
3180 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3181 * Smartcard feature is supported by the USARTx instance.
3182 * @rmtoll CR1 EOBIE LL_USART_IsEnabledIT_EOB
3183 * @param USARTx USART Instance
3184 * @retval State of bit (1 or 0).
3186 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_EOB(USART_TypeDef
*USARTx
)
3188 return ((READ_BIT(USARTx
->CR1
, USART_CR1_EOBIE
) == (USART_CR1_EOBIE
)) ? 1UL : 0UL);
3192 * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled.
3193 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3194 * LIN feature is supported by the USARTx instance.
3195 * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD
3196 * @param USARTx USART Instance
3197 * @retval State of bit (1 or 0).
3199 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef
*USARTx
)
3201 return ((READ_BIT(USARTx
->CR2
, USART_CR2_LBDIE
) == (USART_CR2_LBDIE
)) ? 1UL : 0UL);
3205 * @brief Check if the USART Error Interrupt is enabled or disabled.
3206 * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR
3207 * @param USARTx USART Instance
3208 * @retval State of bit (1 or 0).
3210 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef
*USARTx
)
3212 return ((READ_BIT(USARTx
->CR3
, USART_CR3_EIE
) == (USART_CR3_EIE
)) ? 1UL : 0UL);
3216 * @brief Check if the USART CTS Interrupt is enabled or disabled.
3217 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3218 * Hardware Flow control feature is supported by the USARTx instance.
3219 * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS
3220 * @param USARTx USART Instance
3221 * @retval State of bit (1 or 0).
3223 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef
*USARTx
)
3225 return ((READ_BIT(USARTx
->CR3
, USART_CR3_CTSIE
) == (USART_CR3_CTSIE
)) ? 1UL : 0UL);
3228 #if defined(USART_TCBGT_SUPPORT)
3229 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
3231 * @brief Check if the Smartcard Transmission Complete Before Guard Time Interrupt is enabled or disabled.
3232 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3233 * Smartcard feature is supported by the USARTx instance.
3234 * @rmtoll CR3 TCBGTIE LL_USART_IsEnabledIT_TCBGT
3235 * @param USARTx USART Instance
3236 * @retval State of bit (1 or 0).
3238 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TCBGT(USART_TypeDef
*USARTx
)
3240 return ((READ_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
) == (USART_CR3_TCBGTIE
)) ? 1UL : 0UL);
3248 /** @defgroup USART_LL_EF_DMA_Management DMA_Management
3253 * @brief Enable DMA Mode for reception
3254 * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX
3255 * @param USARTx USART Instance
3258 __STATIC_INLINE
void LL_USART_EnableDMAReq_RX(USART_TypeDef
*USARTx
)
3260 SET_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
3264 * @brief Disable DMA Mode for reception
3265 * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX
3266 * @param USARTx USART Instance
3269 __STATIC_INLINE
void LL_USART_DisableDMAReq_RX(USART_TypeDef
*USARTx
)
3271 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
3275 * @brief Check if DMA Mode is enabled for reception
3276 * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX
3277 * @param USARTx USART Instance
3278 * @retval State of bit (1 or 0).
3280 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef
*USARTx
)
3282 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DMAR
) == (USART_CR3_DMAR
)) ? 1UL : 0UL);
3286 * @brief Enable DMA Mode for transmission
3287 * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX
3288 * @param USARTx USART Instance
3291 __STATIC_INLINE
void LL_USART_EnableDMAReq_TX(USART_TypeDef
*USARTx
)
3293 SET_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
3297 * @brief Disable DMA Mode for transmission
3298 * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX
3299 * @param USARTx USART Instance
3302 __STATIC_INLINE
void LL_USART_DisableDMAReq_TX(USART_TypeDef
*USARTx
)
3304 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
3308 * @brief Check if DMA Mode is enabled for transmission
3309 * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX
3310 * @param USARTx USART Instance
3311 * @retval State of bit (1 or 0).
3313 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef
*USARTx
)
3315 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DMAT
) == (USART_CR3_DMAT
)) ? 1UL : 0UL);
3319 * @brief Enable DMA Disabling on Reception Error
3320 * @rmtoll CR3 DDRE LL_USART_EnableDMADeactOnRxErr
3321 * @param USARTx USART Instance
3324 __STATIC_INLINE
void LL_USART_EnableDMADeactOnRxErr(USART_TypeDef
*USARTx
)
3326 SET_BIT(USARTx
->CR3
, USART_CR3_DDRE
);
3330 * @brief Disable DMA Disabling on Reception Error
3331 * @rmtoll CR3 DDRE LL_USART_DisableDMADeactOnRxErr
3332 * @param USARTx USART Instance
3335 __STATIC_INLINE
void LL_USART_DisableDMADeactOnRxErr(USART_TypeDef
*USARTx
)
3337 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DDRE
);
3341 * @brief Indicate if DMA Disabling on Reception Error is disabled
3342 * @rmtoll CR3 DDRE LL_USART_IsEnabledDMADeactOnRxErr
3343 * @param USARTx USART Instance
3344 * @retval State of bit (1 or 0).
3346 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMADeactOnRxErr(USART_TypeDef
*USARTx
)
3348 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DDRE
) == (USART_CR3_DDRE
)) ? 1UL : 0UL);
3352 * @brief Get the data register address used for DMA transfer
3353 * @rmtoll RDR RDR LL_USART_DMA_GetRegAddr\n
3354 * @rmtoll TDR TDR LL_USART_DMA_GetRegAddr
3355 * @param USARTx USART Instance
3356 * @param Direction This parameter can be one of the following values:
3357 * @arg @ref LL_USART_DMA_REG_DATA_TRANSMIT
3358 * @arg @ref LL_USART_DMA_REG_DATA_RECEIVE
3359 * @retval Address of data register
3361 __STATIC_INLINE
uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef
*USARTx
, uint32_t Direction
)
3363 register uint32_t data_reg_addr
;
3365 if (Direction
== LL_USART_DMA_REG_DATA_TRANSMIT
)
3367 /* return address of TDR register */
3368 data_reg_addr
= (uint32_t) & (USARTx
->TDR
);
3372 /* return address of RDR register */
3373 data_reg_addr
= (uint32_t) & (USARTx
->RDR
);
3376 return data_reg_addr
;
3383 /** @defgroup USART_LL_EF_Data_Management Data_Management
3388 * @brief Read Receiver Data register (Receive Data value, 8 bits)
3389 * @rmtoll RDR RDR LL_USART_ReceiveData8
3390 * @param USARTx USART Instance
3391 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
3393 __STATIC_INLINE
uint8_t LL_USART_ReceiveData8(USART_TypeDef
*USARTx
)
3395 return (uint8_t)(READ_BIT(USARTx
->RDR
, USART_RDR_RDR
));
3399 * @brief Read Receiver Data register (Receive Data value, 9 bits)
3400 * @rmtoll RDR RDR LL_USART_ReceiveData9
3401 * @param USARTx USART Instance
3402 * @retval Value between Min_Data=0x00 and Max_Data=0x1FF
3404 __STATIC_INLINE
uint16_t LL_USART_ReceiveData9(USART_TypeDef
*USARTx
)
3406 return (uint16_t)(READ_BIT(USARTx
->RDR
, USART_RDR_RDR
));
3410 * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits)
3411 * @rmtoll TDR TDR LL_USART_TransmitData8
3412 * @param USARTx USART Instance
3413 * @param Value between Min_Data=0x00 and Max_Data=0xFF
3416 __STATIC_INLINE
void LL_USART_TransmitData8(USART_TypeDef
*USARTx
, uint8_t Value
)
3418 USARTx
->TDR
= Value
;
3422 * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits)
3423 * @rmtoll TDR TDR LL_USART_TransmitData9
3424 * @param USARTx USART Instance
3425 * @param Value between Min_Data=0x00 and Max_Data=0x1FF
3428 __STATIC_INLINE
void LL_USART_TransmitData9(USART_TypeDef
*USARTx
, uint16_t Value
)
3430 USARTx
->TDR
= (uint16_t)(Value
& 0x1FFUL
);
3437 /** @defgroup USART_LL_EF_Execution Execution
3442 * @brief Request an Automatic Baud Rate measurement on next received data frame
3443 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
3444 * Auto Baud Rate detection feature is supported by the USARTx instance.
3445 * @rmtoll RQR ABRRQ LL_USART_RequestAutoBaudRate
3446 * @param USARTx USART Instance
3449 __STATIC_INLINE
void LL_USART_RequestAutoBaudRate(USART_TypeDef
*USARTx
)
3451 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_ABRRQ
);
3455 * @brief Request Break sending
3456 * @rmtoll RQR SBKRQ LL_USART_RequestBreakSending
3457 * @param USARTx USART Instance
3460 __STATIC_INLINE
void LL_USART_RequestBreakSending(USART_TypeDef
*USARTx
)
3462 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_SBKRQ
);
3466 * @brief Put USART in mute mode and set the RWU flag
3467 * @rmtoll RQR MMRQ LL_USART_RequestEnterMuteMode
3468 * @param USARTx USART Instance
3471 __STATIC_INLINE
void LL_USART_RequestEnterMuteMode(USART_TypeDef
*USARTx
)
3473 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_MMRQ
);
3477 * @brief Request a Receive Data flush
3478 * @note Allows to discard the received data without reading them, and avoid an overrun
3480 * @rmtoll RQR RXFRQ LL_USART_RequestRxDataFlush
3481 * @param USARTx USART Instance
3484 __STATIC_INLINE
void LL_USART_RequestRxDataFlush(USART_TypeDef
*USARTx
)
3486 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_RXFRQ
);
3490 * @brief Request a Transmit data flush
3491 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3492 * Smartcard feature is supported by the USARTx instance.
3493 * @rmtoll RQR TXFRQ LL_USART_RequestTxDataFlush
3494 * @param USARTx USART Instance
3497 __STATIC_INLINE
void LL_USART_RequestTxDataFlush(USART_TypeDef
*USARTx
)
3499 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_TXFRQ
);
3506 #if defined(USE_FULL_LL_DRIVER)
3507 /** @defgroup USART_LL_EF_Init Initialization and de-initialization functions
3510 ErrorStatus
LL_USART_DeInit(USART_TypeDef
*USARTx
);
3511 ErrorStatus
LL_USART_Init(USART_TypeDef
*USARTx
, LL_USART_InitTypeDef
*USART_InitStruct
);
3512 void LL_USART_StructInit(LL_USART_InitTypeDef
*USART_InitStruct
);
3513 ErrorStatus
LL_USART_ClockInit(USART_TypeDef
*USARTx
, LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
3514 void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
3518 #endif /* USE_FULL_LL_DRIVER */
3528 #endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 */
3538 #endif /* STM32F7xx_LL_USART_H */
3540 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/