2 ******************************************************************************
3 * @file stm32g4xx_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 STM32G4xx_LL_USART_H
22 #define STM32G4xx_LL_USART_H
28 /* Includes ------------------------------------------------------------------*/
29 #include "stm32g4xx.h"
31 /** @addtogroup STM32G4xx_LL_Driver
35 #if defined (USART1) || defined (USART2) || defined (USART3) || defined (UART4) || defined (UART5)
37 /** @defgroup USART_LL USART
41 /* Private types -------------------------------------------------------------*/
42 /* Private variables ---------------------------------------------------------*/
43 /** @defgroup USART_LL_Private_Variables USART Private Variables
46 /* Array used to get the USART prescaler division decimal values versus @ref USART_LL_EC_PRESCALER values */
47 static const uint32_t USART_PRESCALER_TAB
[] =
66 /* Private constants ---------------------------------------------------------*/
67 /** @defgroup USART_LL_Private_Constants USART Private Constants
74 /* Private macros ------------------------------------------------------------*/
75 #if defined(USE_FULL_LL_DRIVER)
76 /** @defgroup USART_LL_Private_Macros USART Private Macros
82 #endif /*USE_FULL_LL_DRIVER*/
84 /* Exported types ------------------------------------------------------------*/
85 #if defined(USE_FULL_LL_DRIVER)
86 /** @defgroup USART_LL_ES_INIT USART Exported Init structures
91 * @brief LL USART Init Structure definition
95 uint32_t PrescalerValue
; /*!< Specifies the Prescaler to compute the communication baud rate.
96 This parameter can be a value of @ref USART_LL_EC_PRESCALER.
98 This feature can be modified afterwards using unitary function @ref LL_USART_SetPrescaler().*/
100 uint32_t BaudRate
; /*!< This field defines expected Usart communication baud rate.
102 This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/
104 uint32_t DataWidth
; /*!< Specifies the number of data bits transmitted or received in a frame.
105 This parameter can be a value of @ref USART_LL_EC_DATAWIDTH.
107 This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/
109 uint32_t StopBits
; /*!< Specifies the number of stop bits transmitted.
110 This parameter can be a value of @ref USART_LL_EC_STOPBITS.
112 This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/
114 uint32_t Parity
; /*!< Specifies the parity mode.
115 This parameter can be a value of @ref USART_LL_EC_PARITY.
117 This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/
119 uint32_t TransferDirection
; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled.
120 This parameter can be a value of @ref USART_LL_EC_DIRECTION.
122 This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/
124 uint32_t HardwareFlowControl
; /*!< Specifies whether the hardware flow control mode is enabled or disabled.
125 This parameter can be a value of @ref USART_LL_EC_HWCONTROL.
127 This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/
129 uint32_t OverSampling
; /*!< Specifies whether USART oversampling mode is 16 or 8.
130 This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING.
132 This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/
134 } LL_USART_InitTypeDef
;
137 * @brief LL USART Clock Init Structure definition
141 uint32_t ClockOutput
; /*!< Specifies whether the USART clock is enabled or disabled.
142 This parameter can be a value of @ref USART_LL_EC_CLOCK.
144 USART HW configuration can be modified afterwards using unitary functions
145 @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput().
146 For more details, refer to description of this function. */
148 uint32_t ClockPolarity
; /*!< Specifies the steady state of the serial clock.
149 This parameter can be a value of @ref USART_LL_EC_POLARITY.
151 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity().
152 For more details, refer to description of this function. */
154 uint32_t ClockPhase
; /*!< Specifies the clock transition on which the bit capture is made.
155 This parameter can be a value of @ref USART_LL_EC_PHASE.
157 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase().
158 For more details, refer to description of this function. */
160 uint32_t LastBitClockPulse
; /*!< Specifies whether the clock pulse corresponding to the last transmitted
161 data bit (MSB) has to be output on the SCLK pin in synchronous mode.
162 This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE.
164 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput().
165 For more details, refer to description of this function. */
167 } LL_USART_ClockInitTypeDef
;
172 #endif /* USE_FULL_LL_DRIVER */
174 /* Exported constants --------------------------------------------------------*/
175 /** @defgroup USART_LL_Exported_Constants USART Exported Constants
179 /** @defgroup USART_LL_EC_CLEAR_FLAG Clear Flags Defines
180 * @brief Flags defines which can be used with LL_USART_WriteReg function
183 #define LL_USART_ICR_PECF USART_ICR_PECF /*!< Parity error flag */
184 #define LL_USART_ICR_FECF USART_ICR_FECF /*!< Framing error flag */
185 #define LL_USART_ICR_NECF USART_ICR_NECF /*!< Noise error detected flag */
186 #define LL_USART_ICR_ORECF USART_ICR_ORECF /*!< Overrun error flag */
187 #define LL_USART_ICR_IDLECF USART_ICR_IDLECF /*!< Idle line detected flag */
188 #define LL_USART_ICR_TXFECF USART_ICR_TXFECF /*!< TX FIFO Empty Clear flag */
189 #define LL_USART_ICR_TCCF USART_ICR_TCCF /*!< Transmission complete flag */
190 #define LL_USART_ICR_TCBGTCF USART_ICR_TCBGTCF /*!< Transmission completed before guard time flag */
191 #define LL_USART_ICR_LBDCF USART_ICR_LBDCF /*!< LIN break detection flag */
192 #define LL_USART_ICR_CTSCF USART_ICR_CTSCF /*!< CTS flag */
193 #define LL_USART_ICR_RTOCF USART_ICR_RTOCF /*!< Receiver timeout flag */
194 #define LL_USART_ICR_EOBCF USART_ICR_EOBCF /*!< End of block flag */
195 #define LL_USART_ICR_UDRCF USART_ICR_UDRCF /*!< SPI Slave Underrun Clear flag */
196 #define LL_USART_ICR_CMCF USART_ICR_CMCF /*!< Character match flag */
197 #define LL_USART_ICR_WUCF USART_ICR_WUCF /*!< Wakeup from Stop mode flag */
202 /** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines
203 * @brief Flags defines which can be used with LL_USART_ReadReg function
206 #define LL_USART_ISR_PE USART_ISR_PE /*!< Parity error flag */
207 #define LL_USART_ISR_FE USART_ISR_FE /*!< Framing error flag */
208 #define LL_USART_ISR_NE USART_ISR_NE /*!< Noise detected flag */
209 #define LL_USART_ISR_ORE USART_ISR_ORE /*!< Overrun error flag */
210 #define LL_USART_ISR_IDLE USART_ISR_IDLE /*!< Idle line detected flag */
211 #define LL_USART_ISR_RXNE_RXFNE USART_ISR_RXNE_RXFNE /*!< Read data register or RX FIFO not empty flag */
212 #define LL_USART_ISR_TC USART_ISR_TC /*!< Transmission complete flag */
213 #define LL_USART_ISR_TXE_TXFNF USART_ISR_TXE_TXFNF /*!< Transmit data register empty or TX FIFO Not Full flag*/
214 #define LL_USART_ISR_LBDF USART_ISR_LBDF /*!< LIN break detection flag */
215 #define LL_USART_ISR_CTSIF USART_ISR_CTSIF /*!< CTS interrupt flag */
216 #define LL_USART_ISR_CTS USART_ISR_CTS /*!< CTS flag */
217 #define LL_USART_ISR_RTOF USART_ISR_RTOF /*!< Receiver timeout flag */
218 #define LL_USART_ISR_EOBF USART_ISR_EOBF /*!< End of block flag */
219 #define LL_USART_ISR_UDR USART_ISR_UDR /*!< SPI Slave underrun error flag */
220 #define LL_USART_ISR_ABRE USART_ISR_ABRE /*!< Auto baud rate error flag */
221 #define LL_USART_ISR_ABRF USART_ISR_ABRF /*!< Auto baud rate flag */
222 #define LL_USART_ISR_BUSY USART_ISR_BUSY /*!< Busy flag */
223 #define LL_USART_ISR_CMF USART_ISR_CMF /*!< Character match flag */
224 #define LL_USART_ISR_SBKF USART_ISR_SBKF /*!< Send break flag */
225 #define LL_USART_ISR_RWU USART_ISR_RWU /*!< Receiver wakeup from Mute mode flag */
226 #define LL_USART_ISR_WUF USART_ISR_WUF /*!< Wakeup from Stop mode flag */
227 #define LL_USART_ISR_TEACK USART_ISR_TEACK /*!< Transmit enable acknowledge flag */
228 #define LL_USART_ISR_REACK USART_ISR_REACK /*!< Receive enable acknowledge flag */
229 #define LL_USART_ISR_TXFE USART_ISR_TXFE /*!< TX FIFO empty flag */
230 #define LL_USART_ISR_RXFF USART_ISR_RXFF /*!< RX FIFO full flag */
231 #define LL_USART_ISR_TCBGT USART_ISR_TCBGT /*!< Transmission complete before guard time completion flag */
232 #define LL_USART_ISR_RXFT USART_ISR_RXFT /*!< RX FIFO threshold flag */
233 #define LL_USART_ISR_TXFT USART_ISR_TXFT /*!< TX FIFO threshold flag */
238 /** @defgroup USART_LL_EC_IT IT Defines
239 * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions
242 #define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */
243 #define LL_USART_CR1_RXNEIE_RXFNEIE USART_CR1_RXNEIE_RXFNEIE /*!< Read data register and RXFIFO not empty interrupt enable */
244 #define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */
245 #define LL_USART_CR1_TXEIE_TXFNFIE USART_CR1_TXEIE_TXFNFIE /*!< Transmit data register empty and TX FIFO not full interrupt enable */
246 #define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */
247 #define LL_USART_CR1_CMIE USART_CR1_CMIE /*!< Character match interrupt enable */
248 #define LL_USART_CR1_RTOIE USART_CR1_RTOIE /*!< Receiver timeout interrupt enable */
249 #define LL_USART_CR1_EOBIE USART_CR1_EOBIE /*!< End of Block interrupt enable */
250 #define LL_USART_CR1_TXFEIE USART_CR1_TXFEIE /*!< TX FIFO empty interrupt enable */
251 #define LL_USART_CR1_RXFFIE USART_CR1_RXFFIE /*!< RX FIFO full interrupt enable */
252 #define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */
253 #define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */
254 #define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */
255 #define LL_USART_CR3_WUFIE USART_CR3_WUFIE /*!< Wakeup from Stop mode interrupt enable */
256 #define LL_USART_CR3_TXFTIE USART_CR3_TXFTIE /*!< TX FIFO threshold interrupt enable */
257 #define LL_USART_CR3_TCBGTIE USART_CR3_TCBGTIE /*!< Transmission complete before guard time interrupt enable */
258 #define LL_USART_CR3_RXFTIE USART_CR3_RXFTIE /*!< RX FIFO threshold interrupt enable */
263 /** @defgroup USART_LL_EC_FIFOTHRESHOLD FIFO Threshold
266 #define LL_USART_FIFOTHRESHOLD_1_8 0x00000000U /*!< FIFO reaches 1/8 of its depth */
267 #define LL_USART_FIFOTHRESHOLD_1_4 0x00000001U /*!< FIFO reaches 1/4 of its depth */
268 #define LL_USART_FIFOTHRESHOLD_1_2 0x00000002U /*!< FIFO reaches 1/2 of its depth */
269 #define LL_USART_FIFOTHRESHOLD_3_4 0x00000003U /*!< FIFO reaches 3/4 of its depth */
270 #define LL_USART_FIFOTHRESHOLD_7_8 0x00000004U /*!< FIFO reaches 7/8 of its depth */
271 #define LL_USART_FIFOTHRESHOLD_8_8 0x00000005U /*!< FIFO becomes empty for TX and full for RX */
276 /** @defgroup USART_LL_EC_DIRECTION Communication Direction
279 #define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */
280 #define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */
281 #define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */
282 #define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */
287 /** @defgroup USART_LL_EC_PARITY Parity Control
290 #define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */
291 #define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */
292 #define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */
297 /** @defgroup USART_LL_EC_WAKEUP Wakeup
300 #define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */
301 #define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */
306 /** @defgroup USART_LL_EC_DATAWIDTH Datawidth
309 #define LL_USART_DATAWIDTH_7B USART_CR1_M1 /*!< 7 bits word length : Start bit, 7 data bits, n stop bits */
310 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
311 #define LL_USART_DATAWIDTH_9B USART_CR1_M0 /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
316 /** @defgroup USART_LL_EC_OVERSAMPLING Oversampling
319 #define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */
320 #define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */
325 #if defined(USE_FULL_LL_DRIVER)
326 /** @defgroup USART_LL_EC_CLOCK Clock Signal
330 #define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */
331 #define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */
335 #endif /*USE_FULL_LL_DRIVER*/
337 /** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse
340 #define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */
341 #define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */
346 /** @defgroup USART_LL_EC_PHASE Clock Phase
349 #define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */
350 #define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */
355 /** @defgroup USART_LL_EC_POLARITY Clock Polarity
358 #define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/
359 #define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */
364 /** @defgroup USART_LL_EC_PRESCALER Clock Source Prescaler
367 #define LL_USART_PRESCALER_DIV1 0x00000000U /*!< Input clock not devided */
368 #define LL_USART_PRESCALER_DIV2 (USART_PRESC_PRESCALER_0) /*!< Input clock devided by 2 */
369 #define LL_USART_PRESCALER_DIV4 (USART_PRESC_PRESCALER_1) /*!< Input clock devided by 4 */
370 #define LL_USART_PRESCALER_DIV6 (USART_PRESC_PRESCALER_1 | USART_PRESC_PRESCALER_0) /*!< Input clock devided by 6 */
371 #define LL_USART_PRESCALER_DIV8 (USART_PRESC_PRESCALER_2) /*!< Input clock devided by 8 */
372 #define LL_USART_PRESCALER_DIV10 (USART_PRESC_PRESCALER_2 | USART_PRESC_PRESCALER_0) /*!< Input clock devided by 10 */
373 #define LL_USART_PRESCALER_DIV12 (USART_PRESC_PRESCALER_2 | USART_PRESC_PRESCALER_1) /*!< Input clock devided by 12 */
374 #define LL_USART_PRESCALER_DIV16 (USART_PRESC_PRESCALER_2 | USART_PRESC_PRESCALER_1 | USART_PRESC_PRESCALER_0) /*!< Input clock devided by 16 */
375 #define LL_USART_PRESCALER_DIV32 (USART_PRESC_PRESCALER_3) /*!< Input clock devided by 32 */
376 #define LL_USART_PRESCALER_DIV64 (USART_PRESC_PRESCALER_3 | USART_PRESC_PRESCALER_0) /*!< Input clock devided by 64 */
377 #define LL_USART_PRESCALER_DIV128 (USART_PRESC_PRESCALER_3 | USART_PRESC_PRESCALER_1) /*!< Input clock devided by 128 */
378 #define LL_USART_PRESCALER_DIV256 (USART_PRESC_PRESCALER_3 | USART_PRESC_PRESCALER_1 | USART_PRESC_PRESCALER_0) /*!< Input clock devided by 256 */
383 /** @defgroup USART_LL_EC_STOPBITS Stop Bits
386 #define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */
387 #define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */
388 #define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */
389 #define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */
394 /** @defgroup USART_LL_EC_TXRX TX RX Pins Swap
397 #define LL_USART_TXRX_STANDARD 0x00000000U /*!< TX/RX pins are used as defined in standard pinout */
398 #define LL_USART_TXRX_SWAPPED (USART_CR2_SWAP) /*!< TX and RX pins functions are swapped. */
403 /** @defgroup USART_LL_EC_RXPIN_LEVEL RX Pin Active Level Inversion
406 #define LL_USART_RXPIN_LEVEL_STANDARD 0x00000000U /*!< RX pin signal works using the standard logic levels */
407 #define LL_USART_RXPIN_LEVEL_INVERTED (USART_CR2_RXINV) /*!< RX pin signal values are inverted. */
412 /** @defgroup USART_LL_EC_TXPIN_LEVEL TX Pin Active Level Inversion
415 #define LL_USART_TXPIN_LEVEL_STANDARD 0x00000000U /*!< TX pin signal works using the standard logic levels */
416 #define LL_USART_TXPIN_LEVEL_INVERTED (USART_CR2_TXINV) /*!< TX pin signal values are inverted. */
421 /** @defgroup USART_LL_EC_BINARY_LOGIC Binary Data Inversion
424 #define LL_USART_BINARY_LOGIC_POSITIVE 0x00000000U /*!< Logical data from the data register are send/received in positive/direct logic. (1=H, 0=L) */
425 #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. */
430 /** @defgroup USART_LL_EC_BITORDER Bit Order
433 #define LL_USART_BITORDER_LSBFIRST 0x00000000U /*!< data is transmitted/received with data bit 0 first, following the start bit */
434 #define LL_USART_BITORDER_MSBFIRST USART_CR2_MSBFIRST /*!< data is transmitted/received with the MSB first, following the start bit */
439 /** @defgroup USART_LL_EC_AUTOBAUD_DETECT_ON Autobaud Detection
442 #define LL_USART_AUTOBAUD_DETECT_ON_STARTBIT 0x00000000U /*!< Measurement of the start bit is used to detect the baud rate */
443 #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 */
444 #define LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME USART_CR2_ABRMODE_1 /*!< 0x7F frame detection */
445 #define LL_USART_AUTOBAUD_DETECT_ON_55_FRAME (USART_CR2_ABRMODE_1 | USART_CR2_ABRMODE_0) /*!< 0x55 frame detection */
450 /** @defgroup USART_LL_EC_ADDRESS_DETECT Address Length Detection
453 #define LL_USART_ADDRESS_DETECT_4B 0x00000000U /*!< 4-bit address detection method selected */
454 #define LL_USART_ADDRESS_DETECT_7B USART_CR2_ADDM7 /*!< 7-bit address detection (in 8-bit data mode) method selected */
459 /** @defgroup USART_LL_EC_HWCONTROL Hardware Control
462 #define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */
463 #define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */
464 #define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */
465 #define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */
470 /** @defgroup USART_LL_EC_WAKEUP_ON Wakeup Activation
473 #define LL_USART_WAKEUP_ON_ADDRESS 0x00000000U /*!< Wake up active on address match */
474 #define LL_USART_WAKEUP_ON_STARTBIT USART_CR3_WUS_1 /*!< Wake up active on Start bit detection */
475 #define LL_USART_WAKEUP_ON_RXNE (USART_CR3_WUS_0 | USART_CR3_WUS_1) /*!< Wake up active on RXNE */
480 /** @defgroup USART_LL_EC_IRDA_POWER IrDA Power
483 #define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */
484 #define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */
489 /** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length
492 #define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */
493 #define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */
498 /** @defgroup USART_LL_EC_DE_POLARITY Driver Enable Polarity
501 #define LL_USART_DE_POLARITY_HIGH 0x00000000U /*!< DE signal is active high */
502 #define LL_USART_DE_POLARITY_LOW USART_CR3_DEP /*!< DE signal is active low */
507 /** @defgroup USART_LL_EC_DMA_REG_DATA DMA Register Data
510 #define LL_USART_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for transmission */
511 #define LL_USART_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for reception */
520 /* Exported macro ------------------------------------------------------------*/
521 /** @defgroup USART_LL_Exported_Macros USART Exported Macros
525 /** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros
530 * @brief Write a value in USART register
531 * @param __INSTANCE__ USART Instance
532 * @param __REG__ Register to be written
533 * @param __VALUE__ Value to be written in the register
536 #define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
539 * @brief Read a value in USART register
540 * @param __INSTANCE__ USART Instance
541 * @param __REG__ Register to be read
542 * @retval Register value
544 #define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
549 /** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
554 * @brief Compute USARTDIV value according to Peripheral Clock and
555 * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned)
556 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
557 * @param __PRESCALER__ This parameter can be one of the following values:
558 * @arg @ref LL_USART_PRESCALER_DIV1
559 * @arg @ref LL_USART_PRESCALER_DIV2
560 * @arg @ref LL_USART_PRESCALER_DIV4
561 * @arg @ref LL_USART_PRESCALER_DIV6
562 * @arg @ref LL_USART_PRESCALER_DIV8
563 * @arg @ref LL_USART_PRESCALER_DIV10
564 * @arg @ref LL_USART_PRESCALER_DIV12
565 * @arg @ref LL_USART_PRESCALER_DIV16
566 * @arg @ref LL_USART_PRESCALER_DIV32
567 * @arg @ref LL_USART_PRESCALER_DIV64
568 * @arg @ref LL_USART_PRESCALER_DIV128
569 * @arg @ref LL_USART_PRESCALER_DIV256
570 * @param __BAUDRATE__ Baud rate value to achieve
571 * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case
573 #define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __PRESCALER__, __BAUDRATE__) (((((__PERIPHCLK__)/(USART_PRESCALER_TAB[(__PRESCALER__)]))*2U)\
574 + ((__BAUDRATE__)/2U))/(__BAUDRATE__))
577 * @brief Compute USARTDIV value according to Peripheral Clock and
578 * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned)
579 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
580 * @param __PRESCALER__ This parameter can be one of the following values:
581 * @arg @ref LL_USART_PRESCALER_DIV1
582 * @arg @ref LL_USART_PRESCALER_DIV2
583 * @arg @ref LL_USART_PRESCALER_DIV4
584 * @arg @ref LL_USART_PRESCALER_DIV6
585 * @arg @ref LL_USART_PRESCALER_DIV8
586 * @arg @ref LL_USART_PRESCALER_DIV10
587 * @arg @ref LL_USART_PRESCALER_DIV12
588 * @arg @ref LL_USART_PRESCALER_DIV16
589 * @arg @ref LL_USART_PRESCALER_DIV32
590 * @arg @ref LL_USART_PRESCALER_DIV64
591 * @arg @ref LL_USART_PRESCALER_DIV128
592 * @arg @ref LL_USART_PRESCALER_DIV256
593 * @param __BAUDRATE__ Baud rate value to achieve
594 * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case
596 #define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __PRESCALER__, __BAUDRATE__) ((((__PERIPHCLK__)/(USART_PRESCALER_TAB[(__PRESCALER__)]))\
597 + ((__BAUDRATE__)/2U))/(__BAUDRATE__))
607 /* Exported functions --------------------------------------------------------*/
609 /** @defgroup USART_LL_Exported_Functions USART Exported Functions
613 /** @defgroup USART_LL_EF_Configuration Configuration functions
618 * @brief USART Enable
619 * @rmtoll CR1 UE LL_USART_Enable
620 * @param USARTx USART Instance
623 __STATIC_INLINE
void LL_USART_Enable(USART_TypeDef
*USARTx
)
625 SET_BIT(USARTx
->CR1
, USART_CR1_UE
);
629 * @brief USART Disable (all USART prescalers and outputs are disabled)
630 * @note When USART is disabled, USART prescalers and outputs are stopped immediately,
631 * and current operations are discarded. The configuration of the USART is kept, but all the status
632 * flags, in the USARTx_ISR are set to their default values.
633 * @rmtoll CR1 UE LL_USART_Disable
634 * @param USARTx USART Instance
637 __STATIC_INLINE
void LL_USART_Disable(USART_TypeDef
*USARTx
)
639 CLEAR_BIT(USARTx
->CR1
, USART_CR1_UE
);
643 * @brief Indicate if USART is enabled
644 * @rmtoll CR1 UE LL_USART_IsEnabled
645 * @param USARTx USART Instance
646 * @retval State of bit (1 or 0).
648 __STATIC_INLINE
uint32_t LL_USART_IsEnabled(USART_TypeDef
*USARTx
)
650 return ((READ_BIT(USARTx
->CR1
, USART_CR1_UE
) == (USART_CR1_UE
)) ? 1UL : 0UL);
654 * @brief FIFO Mode Enable
655 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
656 * FIFO mode feature is supported by the USARTx instance.
657 * @rmtoll CR1 FIFOEN LL_USART_EnableFIFO
658 * @param USARTx USART Instance
661 __STATIC_INLINE
void LL_USART_EnableFIFO(USART_TypeDef
*USARTx
)
663 SET_BIT(USARTx
->CR1
, USART_CR1_FIFOEN
);
667 * @brief FIFO Mode Disable
668 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
669 * FIFO mode feature is supported by the USARTx instance.
670 * @rmtoll CR1 FIFOEN LL_USART_DisableFIFO
671 * @param USARTx USART Instance
674 __STATIC_INLINE
void LL_USART_DisableFIFO(USART_TypeDef
*USARTx
)
676 CLEAR_BIT(USARTx
->CR1
, USART_CR1_FIFOEN
);
680 * @brief Indicate if FIFO Mode is enabled
681 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
682 * FIFO mode feature is supported by the USARTx instance.
683 * @rmtoll CR1 FIFOEN LL_USART_IsEnabledFIFO
684 * @param USARTx USART Instance
685 * @retval State of bit (1 or 0).
687 __STATIC_INLINE
uint32_t LL_USART_IsEnabledFIFO(USART_TypeDef
*USARTx
)
689 return ((READ_BIT(USARTx
->CR1
, USART_CR1_FIFOEN
) == (USART_CR1_FIFOEN
)) ? 1UL : 0UL);
693 * @brief Configure TX FIFO Threshold
694 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
695 * FIFO mode feature is supported by the USARTx instance.
696 * @rmtoll CR3 TXFTCFG LL_USART_SetTXFIFOThreshold
697 * @param USARTx USART Instance
698 * @param Threshold This parameter can be one of the following values:
699 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
700 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
701 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
702 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
703 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
704 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
707 __STATIC_INLINE
void LL_USART_SetTXFIFOThreshold(USART_TypeDef
*USARTx
, uint32_t Threshold
)
709 MODIFY_REG(USARTx
->CR3
, USART_CR3_TXFTCFG
, Threshold
<< USART_CR3_TXFTCFG_Pos
);
713 * @brief Return TX FIFO Threshold Configuration
714 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
715 * FIFO mode feature is supported by the USARTx instance.
716 * @rmtoll CR3 TXFTCFG LL_USART_GetTXFIFOThreshold
717 * @param USARTx USART Instance
718 * @retval Returned value can be one of the following values:
719 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
720 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
721 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
722 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
723 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
724 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
726 __STATIC_INLINE
uint32_t LL_USART_GetTXFIFOThreshold(USART_TypeDef
*USARTx
)
728 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_TXFTCFG
) >> USART_CR3_TXFTCFG_Pos
);
732 * @brief Configure RX FIFO Threshold
733 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
734 * FIFO mode feature is supported by the USARTx instance.
735 * @rmtoll CR3 RXFTCFG LL_USART_SetRXFIFOThreshold
736 * @param USARTx USART Instance
737 * @param Threshold This parameter can be one of the following values:
738 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
739 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
740 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
741 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
742 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
743 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
746 __STATIC_INLINE
void LL_USART_SetRXFIFOThreshold(USART_TypeDef
*USARTx
, uint32_t Threshold
)
748 MODIFY_REG(USARTx
->CR3
, USART_CR3_RXFTCFG
, Threshold
<< USART_CR3_RXFTCFG_Pos
);
752 * @brief Return RX FIFO Threshold Configuration
753 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
754 * FIFO mode feature is supported by the USARTx instance.
755 * @rmtoll CR3 RXFTCFG LL_USART_GetRXFIFOThreshold
756 * @param USARTx USART Instance
757 * @retval Returned value can be one of the following values:
758 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
759 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
760 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
761 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
762 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
763 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
765 __STATIC_INLINE
uint32_t LL_USART_GetRXFIFOThreshold(USART_TypeDef
*USARTx
)
767 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_RXFTCFG
) >> USART_CR3_RXFTCFG_Pos
);
771 * @brief Configure TX and RX FIFOs Threshold
772 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
773 * FIFO mode feature is supported by the USARTx instance.
774 * @rmtoll CR3 TXFTCFG LL_USART_ConfigFIFOsThreshold\n
775 * CR3 RXFTCFG LL_USART_ConfigFIFOsThreshold
776 * @param USARTx USART Instance
777 * @param TXThreshold This parameter can be one of the following values:
778 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
779 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
780 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
781 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
782 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
783 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
784 * @param RXThreshold This parameter can be one of the following values:
785 * @arg @ref LL_USART_FIFOTHRESHOLD_1_8
786 * @arg @ref LL_USART_FIFOTHRESHOLD_1_4
787 * @arg @ref LL_USART_FIFOTHRESHOLD_1_2
788 * @arg @ref LL_USART_FIFOTHRESHOLD_3_4
789 * @arg @ref LL_USART_FIFOTHRESHOLD_7_8
790 * @arg @ref LL_USART_FIFOTHRESHOLD_8_8
793 __STATIC_INLINE
void LL_USART_ConfigFIFOsThreshold(USART_TypeDef
*USARTx
, uint32_t TXThreshold
, uint32_t RXThreshold
)
795 MODIFY_REG(USARTx
->CR3
, USART_CR3_TXFTCFG
| USART_CR3_RXFTCFG
, (TXThreshold
<< USART_CR3_TXFTCFG_Pos
) | (RXThreshold
<< USART_CR3_RXFTCFG_Pos
));
799 * @brief USART enabled in STOP Mode.
800 * @note When this function is enabled, USART is able to wake up the MCU from Stop mode, provided that
801 * USART clock selection is HSI or LSE in RCC.
802 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
803 * Wake-up from Stop mode feature is supported by the USARTx instance.
804 * @rmtoll CR1 UESM LL_USART_EnableInStopMode
805 * @param USARTx USART Instance
808 __STATIC_INLINE
void LL_USART_EnableInStopMode(USART_TypeDef
*USARTx
)
810 SET_BIT(USARTx
->CR1
, USART_CR1_UESM
);
814 * @brief USART disabled in STOP Mode.
815 * @note When this function is disabled, USART is not able to wake up the MCU from Stop mode
816 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
817 * Wake-up from Stop mode feature is supported by the USARTx instance.
818 * @rmtoll CR1 UESM LL_USART_DisableInStopMode
819 * @param USARTx USART Instance
822 __STATIC_INLINE
void LL_USART_DisableInStopMode(USART_TypeDef
*USARTx
)
824 CLEAR_BIT(USARTx
->CR1
, USART_CR1_UESM
);
828 * @brief Indicate if USART is enabled in STOP Mode (able to wake up MCU from Stop mode or not)
829 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
830 * Wake-up from Stop mode feature is supported by the USARTx instance.
831 * @rmtoll CR1 UESM LL_USART_IsEnabledInStopMode
832 * @param USARTx USART Instance
833 * @retval State of bit (1 or 0).
835 __STATIC_INLINE
uint32_t LL_USART_IsEnabledInStopMode(USART_TypeDef
*USARTx
)
837 return ((READ_BIT(USARTx
->CR1
, USART_CR1_UESM
) == (USART_CR1_UESM
)) ? 1UL : 0UL);
841 * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit)
842 * @rmtoll CR1 RE LL_USART_EnableDirectionRx
843 * @param USARTx USART Instance
846 __STATIC_INLINE
void LL_USART_EnableDirectionRx(USART_TypeDef
*USARTx
)
848 SET_BIT(USARTx
->CR1
, USART_CR1_RE
);
852 * @brief Receiver Disable
853 * @rmtoll CR1 RE LL_USART_DisableDirectionRx
854 * @param USARTx USART Instance
857 __STATIC_INLINE
void LL_USART_DisableDirectionRx(USART_TypeDef
*USARTx
)
859 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RE
);
863 * @brief Transmitter Enable
864 * @rmtoll CR1 TE LL_USART_EnableDirectionTx
865 * @param USARTx USART Instance
868 __STATIC_INLINE
void LL_USART_EnableDirectionTx(USART_TypeDef
*USARTx
)
870 SET_BIT(USARTx
->CR1
, USART_CR1_TE
);
874 * @brief Transmitter Disable
875 * @rmtoll CR1 TE LL_USART_DisableDirectionTx
876 * @param USARTx USART Instance
879 __STATIC_INLINE
void LL_USART_DisableDirectionTx(USART_TypeDef
*USARTx
)
881 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TE
);
885 * @brief Configure simultaneously enabled/disabled states
886 * of Transmitter and Receiver
887 * @rmtoll CR1 RE LL_USART_SetTransferDirection\n
888 * CR1 TE LL_USART_SetTransferDirection
889 * @param USARTx USART Instance
890 * @param TransferDirection This parameter can be one of the following values:
891 * @arg @ref LL_USART_DIRECTION_NONE
892 * @arg @ref LL_USART_DIRECTION_RX
893 * @arg @ref LL_USART_DIRECTION_TX
894 * @arg @ref LL_USART_DIRECTION_TX_RX
897 __STATIC_INLINE
void LL_USART_SetTransferDirection(USART_TypeDef
*USARTx
, uint32_t TransferDirection
)
899 MODIFY_REG(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
, TransferDirection
);
903 * @brief Return enabled/disabled states of Transmitter and Receiver
904 * @rmtoll CR1 RE LL_USART_GetTransferDirection\n
905 * CR1 TE LL_USART_GetTransferDirection
906 * @param USARTx USART Instance
907 * @retval Returned value can be one of the following values:
908 * @arg @ref LL_USART_DIRECTION_NONE
909 * @arg @ref LL_USART_DIRECTION_RX
910 * @arg @ref LL_USART_DIRECTION_TX
911 * @arg @ref LL_USART_DIRECTION_TX_RX
913 __STATIC_INLINE
uint32_t LL_USART_GetTransferDirection(USART_TypeDef
*USARTx
)
915 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_RE
| USART_CR1_TE
));
919 * @brief Configure Parity (enabled/disabled and parity mode if enabled).
920 * @note This function selects if hardware parity control (generation and detection) is enabled or disabled.
921 * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position
922 * (9th or 8th bit depending on data width) and parity is checked on the received data.
923 * @rmtoll CR1 PS LL_USART_SetParity\n
924 * CR1 PCE LL_USART_SetParity
925 * @param USARTx USART Instance
926 * @param Parity This parameter can be one of the following values:
927 * @arg @ref LL_USART_PARITY_NONE
928 * @arg @ref LL_USART_PARITY_EVEN
929 * @arg @ref LL_USART_PARITY_ODD
932 __STATIC_INLINE
void LL_USART_SetParity(USART_TypeDef
*USARTx
, uint32_t Parity
)
934 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
, Parity
);
938 * @brief Return Parity configuration (enabled/disabled and parity mode if enabled)
939 * @rmtoll CR1 PS LL_USART_GetParity\n
940 * CR1 PCE LL_USART_GetParity
941 * @param USARTx USART Instance
942 * @retval Returned value can be one of the following values:
943 * @arg @ref LL_USART_PARITY_NONE
944 * @arg @ref LL_USART_PARITY_EVEN
945 * @arg @ref LL_USART_PARITY_ODD
947 __STATIC_INLINE
uint32_t LL_USART_GetParity(USART_TypeDef
*USARTx
)
949 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
));
953 * @brief Set Receiver Wake Up method from Mute mode.
954 * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod
955 * @param USARTx USART Instance
956 * @param Method This parameter can be one of the following values:
957 * @arg @ref LL_USART_WAKEUP_IDLELINE
958 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
961 __STATIC_INLINE
void LL_USART_SetWakeUpMethod(USART_TypeDef
*USARTx
, uint32_t Method
)
963 MODIFY_REG(USARTx
->CR1
, USART_CR1_WAKE
, Method
);
967 * @brief Return Receiver Wake Up method from Mute mode
968 * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod
969 * @param USARTx USART Instance
970 * @retval Returned value can be one of the following values:
971 * @arg @ref LL_USART_WAKEUP_IDLELINE
972 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
974 __STATIC_INLINE
uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef
*USARTx
)
976 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_WAKE
));
980 * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits)
981 * @rmtoll CR1 M0 LL_USART_SetDataWidth\n
982 * CR1 M1 LL_USART_SetDataWidth
983 * @param USARTx USART Instance
984 * @param DataWidth This parameter can be one of the following values:
985 * @arg @ref LL_USART_DATAWIDTH_7B
986 * @arg @ref LL_USART_DATAWIDTH_8B
987 * @arg @ref LL_USART_DATAWIDTH_9B
990 __STATIC_INLINE
void LL_USART_SetDataWidth(USART_TypeDef
*USARTx
, uint32_t DataWidth
)
992 MODIFY_REG(USARTx
->CR1
, USART_CR1_M
, DataWidth
);
996 * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits)
997 * @rmtoll CR1 M0 LL_USART_GetDataWidth\n
998 * CR1 M1 LL_USART_GetDataWidth
999 * @param USARTx USART Instance
1000 * @retval Returned value can be one of the following values:
1001 * @arg @ref LL_USART_DATAWIDTH_7B
1002 * @arg @ref LL_USART_DATAWIDTH_8B
1003 * @arg @ref LL_USART_DATAWIDTH_9B
1005 __STATIC_INLINE
uint32_t LL_USART_GetDataWidth(USART_TypeDef
*USARTx
)
1007 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_M
));
1011 * @brief Allow switch between Mute Mode and Active mode
1012 * @rmtoll CR1 MME LL_USART_EnableMuteMode
1013 * @param USARTx USART Instance
1016 __STATIC_INLINE
void LL_USART_EnableMuteMode(USART_TypeDef
*USARTx
)
1018 SET_BIT(USARTx
->CR1
, USART_CR1_MME
);
1022 * @brief Prevent Mute Mode use. Set Receiver in active mode permanently.
1023 * @rmtoll CR1 MME LL_USART_DisableMuteMode
1024 * @param USARTx USART Instance
1027 __STATIC_INLINE
void LL_USART_DisableMuteMode(USART_TypeDef
*USARTx
)
1029 CLEAR_BIT(USARTx
->CR1
, USART_CR1_MME
);
1033 * @brief Indicate if switch between Mute Mode and Active mode is allowed
1034 * @rmtoll CR1 MME LL_USART_IsEnabledMuteMode
1035 * @param USARTx USART Instance
1036 * @retval State of bit (1 or 0).
1038 __STATIC_INLINE
uint32_t LL_USART_IsEnabledMuteMode(USART_TypeDef
*USARTx
)
1040 return ((READ_BIT(USARTx
->CR1
, USART_CR1_MME
) == (USART_CR1_MME
)) ? 1UL : 0UL);
1044 * @brief Set Oversampling to 8-bit or 16-bit mode
1045 * @rmtoll CR1 OVER8 LL_USART_SetOverSampling
1046 * @param USARTx USART Instance
1047 * @param OverSampling This parameter can be one of the following values:
1048 * @arg @ref LL_USART_OVERSAMPLING_16
1049 * @arg @ref LL_USART_OVERSAMPLING_8
1052 __STATIC_INLINE
void LL_USART_SetOverSampling(USART_TypeDef
*USARTx
, uint32_t OverSampling
)
1054 MODIFY_REG(USARTx
->CR1
, USART_CR1_OVER8
, OverSampling
);
1058 * @brief Return Oversampling mode
1059 * @rmtoll CR1 OVER8 LL_USART_GetOverSampling
1060 * @param USARTx USART Instance
1061 * @retval Returned value can be one of the following values:
1062 * @arg @ref LL_USART_OVERSAMPLING_16
1063 * @arg @ref LL_USART_OVERSAMPLING_8
1065 __STATIC_INLINE
uint32_t LL_USART_GetOverSampling(USART_TypeDef
*USARTx
)
1067 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_OVER8
));
1071 * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not
1072 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1073 * Synchronous mode is supported by the USARTx instance.
1074 * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput
1075 * @param USARTx USART Instance
1076 * @param LastBitClockPulse This parameter can be one of the following values:
1077 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
1078 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
1081 __STATIC_INLINE
void LL_USART_SetLastClkPulseOutput(USART_TypeDef
*USARTx
, uint32_t LastBitClockPulse
)
1083 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBCL
, LastBitClockPulse
);
1087 * @brief Retrieve Clock pulse of the last data bit output configuration
1088 * (Last bit Clock pulse output to the SCLK pin or not)
1089 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1090 * Synchronous mode is supported by the USARTx instance.
1091 * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput
1092 * @param USARTx USART Instance
1093 * @retval Returned value can be one of the following values:
1094 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
1095 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
1097 __STATIC_INLINE
uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef
*USARTx
)
1099 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBCL
));
1103 * @brief Select the phase of the clock output on the SCLK pin in synchronous mode
1104 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1105 * Synchronous mode is supported by the USARTx instance.
1106 * @rmtoll CR2 CPHA LL_USART_SetClockPhase
1107 * @param USARTx USART Instance
1108 * @param ClockPhase This parameter can be one of the following values:
1109 * @arg @ref LL_USART_PHASE_1EDGE
1110 * @arg @ref LL_USART_PHASE_2EDGE
1113 __STATIC_INLINE
void LL_USART_SetClockPhase(USART_TypeDef
*USARTx
, uint32_t ClockPhase
)
1115 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
, ClockPhase
);
1119 * @brief Return phase of the clock output on the SCLK pin in synchronous mode
1120 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1121 * Synchronous mode is supported by the USARTx instance.
1122 * @rmtoll CR2 CPHA LL_USART_GetClockPhase
1123 * @param USARTx USART Instance
1124 * @retval Returned value can be one of the following values:
1125 * @arg @ref LL_USART_PHASE_1EDGE
1126 * @arg @ref LL_USART_PHASE_2EDGE
1128 __STATIC_INLINE
uint32_t LL_USART_GetClockPhase(USART_TypeDef
*USARTx
)
1130 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPHA
));
1134 * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode
1135 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1136 * Synchronous mode is supported by the USARTx instance.
1137 * @rmtoll CR2 CPOL LL_USART_SetClockPolarity
1138 * @param USARTx USART Instance
1139 * @param ClockPolarity This parameter can be one of the following values:
1140 * @arg @ref LL_USART_POLARITY_LOW
1141 * @arg @ref LL_USART_POLARITY_HIGH
1144 __STATIC_INLINE
void LL_USART_SetClockPolarity(USART_TypeDef
*USARTx
, uint32_t ClockPolarity
)
1146 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPOL
, ClockPolarity
);
1150 * @brief Return polarity of the clock output on the SCLK pin in synchronous mode
1151 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1152 * Synchronous mode is supported by the USARTx instance.
1153 * @rmtoll CR2 CPOL LL_USART_GetClockPolarity
1154 * @param USARTx USART Instance
1155 * @retval Returned value can be one of the following values:
1156 * @arg @ref LL_USART_POLARITY_LOW
1157 * @arg @ref LL_USART_POLARITY_HIGH
1159 __STATIC_INLINE
uint32_t LL_USART_GetClockPolarity(USART_TypeDef
*USARTx
)
1161 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_CPOL
));
1165 * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse)
1166 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1167 * Synchronous mode is supported by the USARTx instance.
1168 * @note Call of this function is equivalent to following function call sequence :
1169 * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function
1170 * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function
1171 * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function
1172 * @rmtoll CR2 CPHA LL_USART_ConfigClock\n
1173 * CR2 CPOL LL_USART_ConfigClock\n
1174 * CR2 LBCL LL_USART_ConfigClock
1175 * @param USARTx USART Instance
1176 * @param Phase This parameter can be one of the following values:
1177 * @arg @ref LL_USART_PHASE_1EDGE
1178 * @arg @ref LL_USART_PHASE_2EDGE
1179 * @param Polarity This parameter can be one of the following values:
1180 * @arg @ref LL_USART_POLARITY_LOW
1181 * @arg @ref LL_USART_POLARITY_HIGH
1182 * @param LBCPOutput This parameter can be one of the following values:
1183 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
1184 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
1187 __STATIC_INLINE
void LL_USART_ConfigClock(USART_TypeDef
*USARTx
, uint32_t Phase
, uint32_t Polarity
, uint32_t LBCPOutput
)
1189 MODIFY_REG(USARTx
->CR2
, USART_CR2_CPHA
| USART_CR2_CPOL
| USART_CR2_LBCL
, Phase
| Polarity
| LBCPOutput
);
1193 * @brief Configure Clock source prescaler for baudrate generator and oversampling
1194 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
1195 * FIFO mode feature is supported by the USARTx instance.
1196 * @rmtoll PRESC PRESCALER LL_USART_SetPrescaler
1197 * @param USARTx USART Instance
1198 * @param PrescalerValue This parameter can be one of the following values:
1199 * @arg @ref LL_USART_PRESCALER_DIV1
1200 * @arg @ref LL_USART_PRESCALER_DIV2
1201 * @arg @ref LL_USART_PRESCALER_DIV4
1202 * @arg @ref LL_USART_PRESCALER_DIV6
1203 * @arg @ref LL_USART_PRESCALER_DIV8
1204 * @arg @ref LL_USART_PRESCALER_DIV10
1205 * @arg @ref LL_USART_PRESCALER_DIV12
1206 * @arg @ref LL_USART_PRESCALER_DIV16
1207 * @arg @ref LL_USART_PRESCALER_DIV32
1208 * @arg @ref LL_USART_PRESCALER_DIV64
1209 * @arg @ref LL_USART_PRESCALER_DIV128
1210 * @arg @ref LL_USART_PRESCALER_DIV256
1213 __STATIC_INLINE
void LL_USART_SetPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
1215 MODIFY_REG(USARTx
->PRESC
, USART_PRESC_PRESCALER
, (uint16_t)PrescalerValue
);
1219 * @brief Retrieve the Clock source prescaler for baudrate generator and oversampling
1220 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
1221 * FIFO mode feature is supported by the USARTx instance.
1222 * @rmtoll PRESC PRESCALER LL_USART_GetPrescaler
1223 * @param USARTx USART Instance
1224 * @retval Returned value can be one of the following values:
1225 * @arg @ref LL_USART_PRESCALER_DIV1
1226 * @arg @ref LL_USART_PRESCALER_DIV2
1227 * @arg @ref LL_USART_PRESCALER_DIV4
1228 * @arg @ref LL_USART_PRESCALER_DIV6
1229 * @arg @ref LL_USART_PRESCALER_DIV8
1230 * @arg @ref LL_USART_PRESCALER_DIV10
1231 * @arg @ref LL_USART_PRESCALER_DIV12
1232 * @arg @ref LL_USART_PRESCALER_DIV16
1233 * @arg @ref LL_USART_PRESCALER_DIV32
1234 * @arg @ref LL_USART_PRESCALER_DIV64
1235 * @arg @ref LL_USART_PRESCALER_DIV128
1236 * @arg @ref LL_USART_PRESCALER_DIV256
1238 __STATIC_INLINE
uint32_t LL_USART_GetPrescaler(USART_TypeDef
*USARTx
)
1240 return (uint32_t)(READ_BIT(USARTx
->PRESC
, USART_PRESC_PRESCALER
));
1244 * @brief Enable Clock output on SCLK pin
1245 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1246 * Synchronous mode is supported by the USARTx instance.
1247 * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput
1248 * @param USARTx USART Instance
1251 __STATIC_INLINE
void LL_USART_EnableSCLKOutput(USART_TypeDef
*USARTx
)
1253 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
1257 * @brief Disable Clock output on SCLK pin
1258 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1259 * Synchronous mode is supported by the USARTx instance.
1260 * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput
1261 * @param USARTx USART Instance
1264 __STATIC_INLINE
void LL_USART_DisableSCLKOutput(USART_TypeDef
*USARTx
)
1266 CLEAR_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
1270 * @brief Indicate if Clock output on SCLK pin is enabled
1271 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1272 * Synchronous mode is supported by the USARTx instance.
1273 * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput
1274 * @param USARTx USART Instance
1275 * @retval State of bit (1 or 0).
1277 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef
*USARTx
)
1279 return ((READ_BIT(USARTx
->CR2
, USART_CR2_CLKEN
) == (USART_CR2_CLKEN
)) ? 1UL : 0UL);
1283 * @brief Set the length of the stop bits
1284 * @rmtoll CR2 STOP LL_USART_SetStopBitsLength
1285 * @param USARTx USART Instance
1286 * @param StopBits This parameter can be one of the following values:
1287 * @arg @ref LL_USART_STOPBITS_0_5
1288 * @arg @ref LL_USART_STOPBITS_1
1289 * @arg @ref LL_USART_STOPBITS_1_5
1290 * @arg @ref LL_USART_STOPBITS_2
1293 __STATIC_INLINE
void LL_USART_SetStopBitsLength(USART_TypeDef
*USARTx
, uint32_t StopBits
)
1295 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
1299 * @brief Retrieve the length of the stop bits
1300 * @rmtoll CR2 STOP LL_USART_GetStopBitsLength
1301 * @param USARTx USART Instance
1302 * @retval Returned value can be one of the following values:
1303 * @arg @ref LL_USART_STOPBITS_0_5
1304 * @arg @ref LL_USART_STOPBITS_1
1305 * @arg @ref LL_USART_STOPBITS_1_5
1306 * @arg @ref LL_USART_STOPBITS_2
1308 __STATIC_INLINE
uint32_t LL_USART_GetStopBitsLength(USART_TypeDef
*USARTx
)
1310 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_STOP
));
1314 * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits)
1315 * @note Call of this function is equivalent to following function call sequence :
1316 * - Data Width configuration using @ref LL_USART_SetDataWidth() function
1317 * - Parity Control and mode configuration using @ref LL_USART_SetParity() function
1318 * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function
1319 * @rmtoll CR1 PS LL_USART_ConfigCharacter\n
1320 * CR1 PCE LL_USART_ConfigCharacter\n
1321 * CR1 M0 LL_USART_ConfigCharacter\n
1322 * CR1 M1 LL_USART_ConfigCharacter\n
1323 * CR2 STOP LL_USART_ConfigCharacter
1324 * @param USARTx USART Instance
1325 * @param DataWidth This parameter can be one of the following values:
1326 * @arg @ref LL_USART_DATAWIDTH_7B
1327 * @arg @ref LL_USART_DATAWIDTH_8B
1328 * @arg @ref LL_USART_DATAWIDTH_9B
1329 * @param Parity This parameter can be one of the following values:
1330 * @arg @ref LL_USART_PARITY_NONE
1331 * @arg @ref LL_USART_PARITY_EVEN
1332 * @arg @ref LL_USART_PARITY_ODD
1333 * @param StopBits This parameter can be one of the following values:
1334 * @arg @ref LL_USART_STOPBITS_0_5
1335 * @arg @ref LL_USART_STOPBITS_1
1336 * @arg @ref LL_USART_STOPBITS_1_5
1337 * @arg @ref LL_USART_STOPBITS_2
1340 __STATIC_INLINE
void LL_USART_ConfigCharacter(USART_TypeDef
*USARTx
, uint32_t DataWidth
, uint32_t Parity
,
1343 MODIFY_REG(USARTx
->CR1
, USART_CR1_PS
| USART_CR1_PCE
| USART_CR1_M
, Parity
| DataWidth
);
1344 MODIFY_REG(USARTx
->CR2
, USART_CR2_STOP
, StopBits
);
1348 * @brief Configure TX/RX pins swapping setting.
1349 * @rmtoll CR2 SWAP LL_USART_SetTXRXSwap
1350 * @param USARTx USART Instance
1351 * @param SwapConfig This parameter can be one of the following values:
1352 * @arg @ref LL_USART_TXRX_STANDARD
1353 * @arg @ref LL_USART_TXRX_SWAPPED
1356 __STATIC_INLINE
void LL_USART_SetTXRXSwap(USART_TypeDef
*USARTx
, uint32_t SwapConfig
)
1358 MODIFY_REG(USARTx
->CR2
, USART_CR2_SWAP
, SwapConfig
);
1362 * @brief Retrieve TX/RX pins swapping configuration.
1363 * @rmtoll CR2 SWAP LL_USART_GetTXRXSwap
1364 * @param USARTx USART Instance
1365 * @retval Returned value can be one of the following values:
1366 * @arg @ref LL_USART_TXRX_STANDARD
1367 * @arg @ref LL_USART_TXRX_SWAPPED
1369 __STATIC_INLINE
uint32_t LL_USART_GetTXRXSwap(USART_TypeDef
*USARTx
)
1371 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_SWAP
));
1375 * @brief Configure RX pin active level logic
1376 * @rmtoll CR2 RXINV LL_USART_SetRXPinLevel
1377 * @param USARTx USART Instance
1378 * @param PinInvMethod This parameter can be one of the following values:
1379 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1380 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1383 __STATIC_INLINE
void LL_USART_SetRXPinLevel(USART_TypeDef
*USARTx
, uint32_t PinInvMethod
)
1385 MODIFY_REG(USARTx
->CR2
, USART_CR2_RXINV
, PinInvMethod
);
1389 * @brief Retrieve RX pin active level logic configuration
1390 * @rmtoll CR2 RXINV LL_USART_GetRXPinLevel
1391 * @param USARTx USART Instance
1392 * @retval Returned value can be one of the following values:
1393 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1394 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1396 __STATIC_INLINE
uint32_t LL_USART_GetRXPinLevel(USART_TypeDef
*USARTx
)
1398 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_RXINV
));
1402 * @brief Configure TX pin active level logic
1403 * @rmtoll CR2 TXINV LL_USART_SetTXPinLevel
1404 * @param USARTx USART Instance
1405 * @param PinInvMethod This parameter can be one of the following values:
1406 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1407 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1410 __STATIC_INLINE
void LL_USART_SetTXPinLevel(USART_TypeDef
*USARTx
, uint32_t PinInvMethod
)
1412 MODIFY_REG(USARTx
->CR2
, USART_CR2_TXINV
, PinInvMethod
);
1416 * @brief Retrieve TX pin active level logic configuration
1417 * @rmtoll CR2 TXINV LL_USART_GetTXPinLevel
1418 * @param USARTx USART Instance
1419 * @retval Returned value can be one of the following values:
1420 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1421 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1423 __STATIC_INLINE
uint32_t LL_USART_GetTXPinLevel(USART_TypeDef
*USARTx
)
1425 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_TXINV
));
1429 * @brief Configure Binary data logic.
1430 * @note Allow to define how Logical data from the data register are send/received :
1431 * either in positive/direct logic (1=H, 0=L) or in negative/inverse logic (1=L, 0=H)
1432 * @rmtoll CR2 DATAINV LL_USART_SetBinaryDataLogic
1433 * @param USARTx USART Instance
1434 * @param DataLogic This parameter can be one of the following values:
1435 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1436 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1439 __STATIC_INLINE
void LL_USART_SetBinaryDataLogic(USART_TypeDef
*USARTx
, uint32_t DataLogic
)
1441 MODIFY_REG(USARTx
->CR2
, USART_CR2_DATAINV
, DataLogic
);
1445 * @brief Retrieve Binary data configuration
1446 * @rmtoll CR2 DATAINV LL_USART_GetBinaryDataLogic
1447 * @param USARTx USART Instance
1448 * @retval Returned value can be one of the following values:
1449 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1450 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1452 __STATIC_INLINE
uint32_t LL_USART_GetBinaryDataLogic(USART_TypeDef
*USARTx
)
1454 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_DATAINV
));
1458 * @brief Configure transfer bit order (either Less or Most Significant Bit First)
1459 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1460 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1461 * @rmtoll CR2 MSBFIRST LL_USART_SetTransferBitOrder
1462 * @param USARTx USART Instance
1463 * @param BitOrder This parameter can be one of the following values:
1464 * @arg @ref LL_USART_BITORDER_LSBFIRST
1465 * @arg @ref LL_USART_BITORDER_MSBFIRST
1468 __STATIC_INLINE
void LL_USART_SetTransferBitOrder(USART_TypeDef
*USARTx
, uint32_t BitOrder
)
1470 MODIFY_REG(USARTx
->CR2
, USART_CR2_MSBFIRST
, BitOrder
);
1474 * @brief Return transfer bit order (either Less or Most Significant Bit First)
1475 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1476 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1477 * @rmtoll CR2 MSBFIRST LL_USART_GetTransferBitOrder
1478 * @param USARTx USART Instance
1479 * @retval Returned value can be one of the following values:
1480 * @arg @ref LL_USART_BITORDER_LSBFIRST
1481 * @arg @ref LL_USART_BITORDER_MSBFIRST
1483 __STATIC_INLINE
uint32_t LL_USART_GetTransferBitOrder(USART_TypeDef
*USARTx
)
1485 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_MSBFIRST
));
1489 * @brief Enable Auto Baud-Rate Detection
1490 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1491 * Auto Baud Rate detection feature is supported by the USARTx instance.
1492 * @rmtoll CR2 ABREN LL_USART_EnableAutoBaudRate
1493 * @param USARTx USART Instance
1496 __STATIC_INLINE
void LL_USART_EnableAutoBaudRate(USART_TypeDef
*USARTx
)
1498 SET_BIT(USARTx
->CR2
, USART_CR2_ABREN
);
1502 * @brief Disable Auto Baud-Rate Detection
1503 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1504 * Auto Baud Rate detection feature is supported by the USARTx instance.
1505 * @rmtoll CR2 ABREN LL_USART_DisableAutoBaudRate
1506 * @param USARTx USART Instance
1509 __STATIC_INLINE
void LL_USART_DisableAutoBaudRate(USART_TypeDef
*USARTx
)
1511 CLEAR_BIT(USARTx
->CR2
, USART_CR2_ABREN
);
1515 * @brief Indicate if Auto Baud-Rate Detection mechanism is enabled
1516 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1517 * Auto Baud Rate detection feature is supported by the USARTx instance.
1518 * @rmtoll CR2 ABREN LL_USART_IsEnabledAutoBaud
1519 * @param USARTx USART Instance
1520 * @retval State of bit (1 or 0).
1522 __STATIC_INLINE
uint32_t LL_USART_IsEnabledAutoBaud(USART_TypeDef
*USARTx
)
1524 return ((READ_BIT(USARTx
->CR2
, USART_CR2_ABREN
) == (USART_CR2_ABREN
)) ? 1UL : 0UL);
1528 * @brief Set Auto Baud-Rate mode bits
1529 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1530 * Auto Baud Rate detection feature is supported by the USARTx instance.
1531 * @rmtoll CR2 ABRMODE LL_USART_SetAutoBaudRateMode
1532 * @param USARTx USART Instance
1533 * @param AutoBaudRateMode This parameter can be one of the following values:
1534 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1535 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1536 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1537 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1540 __STATIC_INLINE
void LL_USART_SetAutoBaudRateMode(USART_TypeDef
*USARTx
, uint32_t AutoBaudRateMode
)
1542 MODIFY_REG(USARTx
->CR2
, USART_CR2_ABRMODE
, AutoBaudRateMode
);
1546 * @brief Return Auto Baud-Rate mode
1547 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1548 * Auto Baud Rate detection feature is supported by the USARTx instance.
1549 * @rmtoll CR2 ABRMODE LL_USART_GetAutoBaudRateMode
1550 * @param USARTx USART Instance
1551 * @retval Returned value can be one of the following values:
1552 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1553 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1554 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1555 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1557 __STATIC_INLINE
uint32_t LL_USART_GetAutoBaudRateMode(USART_TypeDef
*USARTx
)
1559 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ABRMODE
));
1563 * @brief Enable Receiver Timeout
1564 * @rmtoll CR2 RTOEN LL_USART_EnableRxTimeout
1565 * @param USARTx USART Instance
1568 __STATIC_INLINE
void LL_USART_EnableRxTimeout(USART_TypeDef
*USARTx
)
1570 SET_BIT(USARTx
->CR2
, USART_CR2_RTOEN
);
1574 * @brief Disable Receiver Timeout
1575 * @rmtoll CR2 RTOEN LL_USART_DisableRxTimeout
1576 * @param USARTx USART Instance
1579 __STATIC_INLINE
void LL_USART_DisableRxTimeout(USART_TypeDef
*USARTx
)
1581 CLEAR_BIT(USARTx
->CR2
, USART_CR2_RTOEN
);
1585 * @brief Indicate if Receiver Timeout feature is enabled
1586 * @rmtoll CR2 RTOEN LL_USART_IsEnabledRxTimeout
1587 * @param USARTx USART Instance
1588 * @retval State of bit (1 or 0).
1590 __STATIC_INLINE
uint32_t LL_USART_IsEnabledRxTimeout(USART_TypeDef
*USARTx
)
1592 return ((READ_BIT(USARTx
->CR2
, USART_CR2_RTOEN
) == (USART_CR2_RTOEN
)) ? 1UL : 0UL);
1596 * @brief Set Address of the USART node.
1597 * @note This is used in multiprocessor communication during Mute mode or Stop mode,
1598 * for wake up with address mark detection.
1599 * @note 4bits address node is used when 4-bit Address Detection is selected in ADDM7.
1600 * (b7-b4 should be set to 0)
1601 * 8bits address node is used when 7-bit Address Detection is selected in ADDM7.
1602 * (This is used in multiprocessor communication during Mute mode or Stop mode,
1603 * for wake up with 7-bit address mark detection.
1604 * The MSB of the character sent by the transmitter should be equal to 1.
1605 * It may also be used for character detection during normal reception,
1606 * Mute mode inactive (for example, end of block detection in ModBus protocol).
1607 * In this case, the whole received character (8-bit) is compared to the ADD[7:0]
1608 * value and CMF flag is set on match)
1609 * @rmtoll CR2 ADD LL_USART_ConfigNodeAddress\n
1610 * CR2 ADDM7 LL_USART_ConfigNodeAddress
1611 * @param USARTx USART Instance
1612 * @param AddressLen This parameter can be one of the following values:
1613 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1614 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1615 * @param NodeAddress 4 or 7 bit Address of the USART node.
1618 __STATIC_INLINE
void LL_USART_ConfigNodeAddress(USART_TypeDef
*USARTx
, uint32_t AddressLen
, uint32_t NodeAddress
)
1620 MODIFY_REG(USARTx
->CR2
, USART_CR2_ADD
| USART_CR2_ADDM7
,
1621 (uint32_t)(AddressLen
| (NodeAddress
<< USART_CR2_ADD_Pos
)));
1625 * @brief Return 8 bit Address of the USART node as set in ADD field of CR2.
1626 * @note If 4-bit Address Detection is selected in ADDM7,
1627 * only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant)
1628 * If 7-bit Address Detection is selected in ADDM7,
1629 * only 8bits (b7-b0) of returned value are relevant (b31-b8 are not relevant)
1630 * @rmtoll CR2 ADD LL_USART_GetNodeAddress
1631 * @param USARTx USART Instance
1632 * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255)
1634 __STATIC_INLINE
uint32_t LL_USART_GetNodeAddress(USART_TypeDef
*USARTx
)
1636 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ADD
) >> USART_CR2_ADD_Pos
);
1640 * @brief Return Length of Node Address used in Address Detection mode (7-bit or 4-bit)
1641 * @rmtoll CR2 ADDM7 LL_USART_GetNodeAddressLen
1642 * @param USARTx USART Instance
1643 * @retval Returned value can be one of the following values:
1644 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1645 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1647 __STATIC_INLINE
uint32_t LL_USART_GetNodeAddressLen(USART_TypeDef
*USARTx
)
1649 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_ADDM7
));
1653 * @brief Enable RTS HW Flow Control
1654 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1655 * Hardware Flow control feature is supported by the USARTx instance.
1656 * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl
1657 * @param USARTx USART Instance
1660 __STATIC_INLINE
void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1662 SET_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
1666 * @brief Disable RTS HW Flow Control
1667 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1668 * Hardware Flow control feature is supported by the USARTx instance.
1669 * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl
1670 * @param USARTx USART Instance
1673 __STATIC_INLINE
void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1675 CLEAR_BIT(USARTx
->CR3
, USART_CR3_RTSE
);
1679 * @brief Enable CTS HW Flow Control
1680 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1681 * Hardware Flow control feature is supported by the USARTx instance.
1682 * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl
1683 * @param USARTx USART Instance
1686 __STATIC_INLINE
void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1688 SET_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
1692 * @brief Disable CTS HW Flow Control
1693 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1694 * Hardware Flow control feature is supported by the USARTx instance.
1695 * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl
1696 * @param USARTx USART Instance
1699 __STATIC_INLINE
void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef
*USARTx
)
1701 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSE
);
1705 * @brief Configure HW Flow Control mode (both CTS and RTS)
1706 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1707 * Hardware Flow control feature is supported by the USARTx instance.
1708 * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n
1709 * CR3 CTSE LL_USART_SetHWFlowCtrl
1710 * @param USARTx USART Instance
1711 * @param HardwareFlowControl This parameter can be one of the following values:
1712 * @arg @ref LL_USART_HWCONTROL_NONE
1713 * @arg @ref LL_USART_HWCONTROL_RTS
1714 * @arg @ref LL_USART_HWCONTROL_CTS
1715 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1718 __STATIC_INLINE
void LL_USART_SetHWFlowCtrl(USART_TypeDef
*USARTx
, uint32_t HardwareFlowControl
)
1720 MODIFY_REG(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
, HardwareFlowControl
);
1724 * @brief Return HW Flow Control configuration (both CTS and RTS)
1725 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1726 * Hardware Flow control feature is supported by the USARTx instance.
1727 * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n
1728 * CR3 CTSE LL_USART_GetHWFlowCtrl
1729 * @param USARTx USART Instance
1730 * @retval Returned value can be one of the following values:
1731 * @arg @ref LL_USART_HWCONTROL_NONE
1732 * @arg @ref LL_USART_HWCONTROL_RTS
1733 * @arg @ref LL_USART_HWCONTROL_CTS
1734 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1736 __STATIC_INLINE
uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef
*USARTx
)
1738 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_RTSE
| USART_CR3_CTSE
));
1742 * @brief Enable One bit sampling method
1743 * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp
1744 * @param USARTx USART Instance
1747 __STATIC_INLINE
void LL_USART_EnableOneBitSamp(USART_TypeDef
*USARTx
)
1749 SET_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1753 * @brief Disable One bit sampling method
1754 * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp
1755 * @param USARTx USART Instance
1758 __STATIC_INLINE
void LL_USART_DisableOneBitSamp(USART_TypeDef
*USARTx
)
1760 CLEAR_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
);
1764 * @brief Indicate if One bit sampling method is enabled
1765 * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp
1766 * @param USARTx USART Instance
1767 * @retval State of bit (1 or 0).
1769 __STATIC_INLINE
uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef
*USARTx
)
1771 return ((READ_BIT(USARTx
->CR3
, USART_CR3_ONEBIT
) == (USART_CR3_ONEBIT
)) ? 1UL : 0UL);
1775 * @brief Enable Overrun detection
1776 * @rmtoll CR3 OVRDIS LL_USART_EnableOverrunDetect
1777 * @param USARTx USART Instance
1780 __STATIC_INLINE
void LL_USART_EnableOverrunDetect(USART_TypeDef
*USARTx
)
1782 CLEAR_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
);
1786 * @brief Disable Overrun detection
1787 * @rmtoll CR3 OVRDIS LL_USART_DisableOverrunDetect
1788 * @param USARTx USART Instance
1791 __STATIC_INLINE
void LL_USART_DisableOverrunDetect(USART_TypeDef
*USARTx
)
1793 SET_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
);
1797 * @brief Indicate if Overrun detection is enabled
1798 * @rmtoll CR3 OVRDIS LL_USART_IsEnabledOverrunDetect
1799 * @param USARTx USART Instance
1800 * @retval State of bit (1 or 0).
1802 __STATIC_INLINE
uint32_t LL_USART_IsEnabledOverrunDetect(USART_TypeDef
*USARTx
)
1804 return ((READ_BIT(USARTx
->CR3
, USART_CR3_OVRDIS
) != USART_CR3_OVRDIS
) ? 1UL : 0UL);
1808 * @brief Select event type for Wake UP Interrupt Flag (WUS[1:0] bits)
1809 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
1810 * Wake-up from Stop mode feature is supported by the USARTx instance.
1811 * @rmtoll CR3 WUS LL_USART_SetWKUPType
1812 * @param USARTx USART Instance
1813 * @param Type This parameter can be one of the following values:
1814 * @arg @ref LL_USART_WAKEUP_ON_ADDRESS
1815 * @arg @ref LL_USART_WAKEUP_ON_STARTBIT
1816 * @arg @ref LL_USART_WAKEUP_ON_RXNE
1819 __STATIC_INLINE
void LL_USART_SetWKUPType(USART_TypeDef
*USARTx
, uint32_t Type
)
1821 MODIFY_REG(USARTx
->CR3
, USART_CR3_WUS
, Type
);
1825 * @brief Return event type for Wake UP Interrupt Flag (WUS[1:0] bits)
1826 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
1827 * Wake-up from Stop mode feature is supported by the USARTx instance.
1828 * @rmtoll CR3 WUS LL_USART_GetWKUPType
1829 * @param USARTx USART Instance
1830 * @retval Returned value can be one of the following values:
1831 * @arg @ref LL_USART_WAKEUP_ON_ADDRESS
1832 * @arg @ref LL_USART_WAKEUP_ON_STARTBIT
1833 * @arg @ref LL_USART_WAKEUP_ON_RXNE
1835 __STATIC_INLINE
uint32_t LL_USART_GetWKUPType(USART_TypeDef
*USARTx
)
1837 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_WUS
));
1841 * @brief Configure USART BRR register for achieving expected Baud Rate value.
1842 * @note Compute and set USARTDIV value in BRR Register (full BRR content)
1843 * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values
1844 * @note Peripheral clock and Baud rate values provided as function parameters should be valid
1845 * (Baud rate value != 0)
1846 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1847 * @rmtoll BRR BRR LL_USART_SetBaudRate
1848 * @param USARTx USART Instance
1849 * @param PeriphClk Peripheral Clock
1850 * @param PrescalerValue This parameter can be one of the following values:
1851 * @arg @ref LL_USART_PRESCALER_DIV1
1852 * @arg @ref LL_USART_PRESCALER_DIV2
1853 * @arg @ref LL_USART_PRESCALER_DIV4
1854 * @arg @ref LL_USART_PRESCALER_DIV6
1855 * @arg @ref LL_USART_PRESCALER_DIV8
1856 * @arg @ref LL_USART_PRESCALER_DIV10
1857 * @arg @ref LL_USART_PRESCALER_DIV12
1858 * @arg @ref LL_USART_PRESCALER_DIV16
1859 * @arg @ref LL_USART_PRESCALER_DIV32
1860 * @arg @ref LL_USART_PRESCALER_DIV64
1861 * @arg @ref LL_USART_PRESCALER_DIV128
1862 * @arg @ref LL_USART_PRESCALER_DIV256
1863 * @param OverSampling This parameter can be one of the following values:
1864 * @arg @ref LL_USART_OVERSAMPLING_16
1865 * @arg @ref LL_USART_OVERSAMPLING_8
1866 * @param BaudRate Baud Rate
1869 __STATIC_INLINE
void LL_USART_SetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t PrescalerValue
,
1870 uint32_t OverSampling
,
1874 register uint32_t brrtemp
;
1876 if (PrescalerValue
> LL_USART_PRESCALER_DIV256
)
1878 /* Do not overstep the size of USART_PRESCALER_TAB */
1880 else if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1882 usartdiv
= (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk
, (uint8_t)PrescalerValue
, BaudRate
));
1883 brrtemp
= usartdiv
& 0xFFF0U
;
1884 brrtemp
|= (uint16_t)((usartdiv
& (uint16_t)0x000FU
) >> 1U);
1885 USARTx
->BRR
= brrtemp
;
1889 USARTx
->BRR
= (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk
, (uint8_t)PrescalerValue
, BaudRate
));
1894 * @brief Return current Baud Rate value, according to USARTDIV present in BRR register
1895 * (full BRR content), and to used Peripheral Clock and Oversampling mode values
1896 * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned.
1897 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1898 * @rmtoll BRR BRR LL_USART_GetBaudRate
1899 * @param USARTx USART Instance
1900 * @param PeriphClk Peripheral Clock
1901 * @param PrescalerValue This parameter can be one of the following values:
1902 * @arg @ref LL_USART_PRESCALER_DIV1
1903 * @arg @ref LL_USART_PRESCALER_DIV2
1904 * @arg @ref LL_USART_PRESCALER_DIV4
1905 * @arg @ref LL_USART_PRESCALER_DIV6
1906 * @arg @ref LL_USART_PRESCALER_DIV8
1907 * @arg @ref LL_USART_PRESCALER_DIV10
1908 * @arg @ref LL_USART_PRESCALER_DIV12
1909 * @arg @ref LL_USART_PRESCALER_DIV16
1910 * @arg @ref LL_USART_PRESCALER_DIV32
1911 * @arg @ref LL_USART_PRESCALER_DIV64
1912 * @arg @ref LL_USART_PRESCALER_DIV128
1913 * @arg @ref LL_USART_PRESCALER_DIV256
1914 * @param OverSampling This parameter can be one of the following values:
1915 * @arg @ref LL_USART_OVERSAMPLING_16
1916 * @arg @ref LL_USART_OVERSAMPLING_8
1919 __STATIC_INLINE
uint32_t LL_USART_GetBaudRate(USART_TypeDef
*USARTx
, uint32_t PeriphClk
, uint32_t PrescalerValue
,
1920 uint32_t OverSampling
)
1922 register uint32_t usartdiv
;
1923 register uint32_t brrresult
= 0x0U
;
1924 register uint32_t periphclkpresc
= (uint32_t)(PeriphClk
/ (USART_PRESCALER_TAB
[(uint8_t)PrescalerValue
]));
1926 usartdiv
= USARTx
->BRR
;
1930 /* Do not perform a division by 0 */
1932 else if (OverSampling
== LL_USART_OVERSAMPLING_8
)
1934 usartdiv
= (uint16_t)((usartdiv
& 0xFFF0U
) | ((usartdiv
& 0x0007U
) << 1U)) ;
1937 brrresult
= (periphclkpresc
* 2U) / usartdiv
;
1942 if ((usartdiv
& 0xFFFFU
) != 0U)
1944 brrresult
= periphclkpresc
/ usartdiv
;
1951 * @brief Set Receiver Time Out Value (expressed in nb of bits duration)
1952 * @rmtoll RTOR RTO LL_USART_SetRxTimeout
1953 * @param USARTx USART Instance
1954 * @param Timeout Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1957 __STATIC_INLINE
void LL_USART_SetRxTimeout(USART_TypeDef
*USARTx
, uint32_t Timeout
)
1959 MODIFY_REG(USARTx
->RTOR
, USART_RTOR_RTO
, Timeout
);
1963 * @brief Get Receiver Time Out Value (expressed in nb of bits duration)
1964 * @rmtoll RTOR RTO LL_USART_GetRxTimeout
1965 * @param USARTx USART Instance
1966 * @retval Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1968 __STATIC_INLINE
uint32_t LL_USART_GetRxTimeout(USART_TypeDef
*USARTx
)
1970 return (uint32_t)(READ_BIT(USARTx
->RTOR
, USART_RTOR_RTO
));
1974 * @brief Set Block Length value in reception
1975 * @rmtoll RTOR BLEN LL_USART_SetBlockLength
1976 * @param USARTx USART Instance
1977 * @param BlockLength Value between Min_Data=0x00 and Max_Data=0xFF
1980 __STATIC_INLINE
void LL_USART_SetBlockLength(USART_TypeDef
*USARTx
, uint32_t BlockLength
)
1982 MODIFY_REG(USARTx
->RTOR
, USART_RTOR_BLEN
, BlockLength
<< USART_RTOR_BLEN_Pos
);
1986 * @brief Get Block Length value in reception
1987 * @rmtoll RTOR BLEN LL_USART_GetBlockLength
1988 * @param USARTx USART Instance
1989 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1991 __STATIC_INLINE
uint32_t LL_USART_GetBlockLength(USART_TypeDef
*USARTx
)
1993 return (uint32_t)(READ_BIT(USARTx
->RTOR
, USART_RTOR_BLEN
) >> USART_RTOR_BLEN_Pos
);
2000 /** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature
2005 * @brief Enable IrDA mode
2006 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2007 * IrDA feature is supported by the USARTx instance.
2008 * @rmtoll CR3 IREN LL_USART_EnableIrda
2009 * @param USARTx USART Instance
2012 __STATIC_INLINE
void LL_USART_EnableIrda(USART_TypeDef
*USARTx
)
2014 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
2018 * @brief Disable IrDA mode
2019 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2020 * IrDA feature is supported by the USARTx instance.
2021 * @rmtoll CR3 IREN LL_USART_DisableIrda
2022 * @param USARTx USART Instance
2025 __STATIC_INLINE
void LL_USART_DisableIrda(USART_TypeDef
*USARTx
)
2027 CLEAR_BIT(USARTx
->CR3
, USART_CR3_IREN
);
2031 * @brief Indicate if IrDA mode is enabled
2032 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2033 * IrDA feature is supported by the USARTx instance.
2034 * @rmtoll CR3 IREN LL_USART_IsEnabledIrda
2035 * @param USARTx USART Instance
2036 * @retval State of bit (1 or 0).
2038 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIrda(USART_TypeDef
*USARTx
)
2040 return ((READ_BIT(USARTx
->CR3
, USART_CR3_IREN
) == (USART_CR3_IREN
)) ? 1UL : 0UL);
2044 * @brief Configure IrDA Power Mode (Normal or Low Power)
2045 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2046 * IrDA feature is supported by the USARTx instance.
2047 * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode
2048 * @param USARTx USART Instance
2049 * @param PowerMode This parameter can be one of the following values:
2050 * @arg @ref LL_USART_IRDA_POWER_NORMAL
2051 * @arg @ref LL_USART_IRDA_POWER_LOW
2054 __STATIC_INLINE
void LL_USART_SetIrdaPowerMode(USART_TypeDef
*USARTx
, uint32_t PowerMode
)
2056 MODIFY_REG(USARTx
->CR3
, USART_CR3_IRLP
, PowerMode
);
2060 * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power)
2061 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2062 * IrDA feature is supported by the USARTx instance.
2063 * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode
2064 * @param USARTx USART Instance
2065 * @retval Returned value can be one of the following values:
2066 * @arg @ref LL_USART_IRDA_POWER_NORMAL
2067 * @arg @ref LL_USART_PHASE_2EDGE
2069 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef
*USARTx
)
2071 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_IRLP
));
2075 * @brief Set Irda prescaler value, used for dividing the USART clock source
2076 * to achieve the Irda Low Power frequency (8 bits value)
2077 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2078 * IrDA feature is supported by the USARTx instance.
2079 * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler
2080 * @param USARTx USART Instance
2081 * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF
2084 __STATIC_INLINE
void LL_USART_SetIrdaPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
2086 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_PSC
, (uint16_t)PrescalerValue
);
2090 * @brief Return Irda prescaler value, used for dividing the USART clock source
2091 * to achieve the Irda Low Power frequency (8 bits value)
2092 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2093 * IrDA feature is supported by the USARTx instance.
2094 * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler
2095 * @param USARTx USART Instance
2096 * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF)
2098 __STATIC_INLINE
uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef
*USARTx
)
2100 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
2107 /** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature
2112 * @brief Enable Smartcard NACK transmission
2113 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2114 * Smartcard feature is supported by the USARTx instance.
2115 * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK
2116 * @param USARTx USART Instance
2119 __STATIC_INLINE
void LL_USART_EnableSmartcardNACK(USART_TypeDef
*USARTx
)
2121 SET_BIT(USARTx
->CR3
, USART_CR3_NACK
);
2125 * @brief Disable Smartcard NACK transmission
2126 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2127 * Smartcard feature is supported by the USARTx instance.
2128 * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK
2129 * @param USARTx USART Instance
2132 __STATIC_INLINE
void LL_USART_DisableSmartcardNACK(USART_TypeDef
*USARTx
)
2134 CLEAR_BIT(USARTx
->CR3
, USART_CR3_NACK
);
2138 * @brief Indicate if Smartcard NACK transmission is enabled
2139 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2140 * Smartcard feature is supported by the USARTx instance.
2141 * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK
2142 * @param USARTx USART Instance
2143 * @retval State of bit (1 or 0).
2145 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef
*USARTx
)
2147 return ((READ_BIT(USARTx
->CR3
, USART_CR3_NACK
) == (USART_CR3_NACK
)) ? 1UL : 0UL);
2151 * @brief Enable Smartcard mode
2152 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2153 * Smartcard feature is supported by the USARTx instance.
2154 * @rmtoll CR3 SCEN LL_USART_EnableSmartcard
2155 * @param USARTx USART Instance
2158 __STATIC_INLINE
void LL_USART_EnableSmartcard(USART_TypeDef
*USARTx
)
2160 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
2164 * @brief Disable Smartcard mode
2165 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2166 * Smartcard feature is supported by the USARTx instance.
2167 * @rmtoll CR3 SCEN LL_USART_DisableSmartcard
2168 * @param USARTx USART Instance
2171 __STATIC_INLINE
void LL_USART_DisableSmartcard(USART_TypeDef
*USARTx
)
2173 CLEAR_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
2177 * @brief Indicate if Smartcard mode is enabled
2178 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2179 * Smartcard feature is supported by the USARTx instance.
2180 * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard
2181 * @param USARTx USART Instance
2182 * @retval State of bit (1 or 0).
2184 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef
*USARTx
)
2186 return ((READ_BIT(USARTx
->CR3
, USART_CR3_SCEN
) == (USART_CR3_SCEN
)) ? 1UL : 0UL);
2190 * @brief Set Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
2191 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2192 * Smartcard feature is supported by the USARTx instance.
2193 * @note This bit-field specifies the number of retries in transmit and receive, in Smartcard mode.
2194 * In transmission mode, it specifies the number of automatic retransmission retries, before
2195 * generating a transmission error (FE bit set).
2196 * In reception mode, it specifies the number or erroneous reception trials, before generating a
2197 * reception error (RXNE and PE bits set)
2198 * @rmtoll CR3 SCARCNT LL_USART_SetSmartcardAutoRetryCount
2199 * @param USARTx USART Instance
2200 * @param AutoRetryCount Value between Min_Data=0 and Max_Data=7
2203 __STATIC_INLINE
void LL_USART_SetSmartcardAutoRetryCount(USART_TypeDef
*USARTx
, uint32_t AutoRetryCount
)
2205 MODIFY_REG(USARTx
->CR3
, USART_CR3_SCARCNT
, AutoRetryCount
<< USART_CR3_SCARCNT_Pos
);
2209 * @brief Return Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
2210 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2211 * Smartcard feature is supported by the USARTx instance.
2212 * @rmtoll CR3 SCARCNT LL_USART_GetSmartcardAutoRetryCount
2213 * @param USARTx USART Instance
2214 * @retval Smartcard Auto-Retry Count value (Value between Min_Data=0 and Max_Data=7)
2216 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardAutoRetryCount(USART_TypeDef
*USARTx
)
2218 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_SCARCNT
) >> USART_CR3_SCARCNT_Pos
);
2222 * @brief Set Smartcard prescaler value, used for dividing the USART clock
2223 * source to provide the SMARTCARD Clock (5 bits value)
2224 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2225 * Smartcard feature is supported by the USARTx instance.
2226 * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler
2227 * @param USARTx USART Instance
2228 * @param PrescalerValue Value between Min_Data=0 and Max_Data=31
2231 __STATIC_INLINE
void LL_USART_SetSmartcardPrescaler(USART_TypeDef
*USARTx
, uint32_t PrescalerValue
)
2233 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_PSC
, (uint16_t)PrescalerValue
);
2237 * @brief Return Smartcard prescaler value, used for dividing the USART clock
2238 * source to provide the SMARTCARD Clock (5 bits value)
2239 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2240 * Smartcard feature is supported by the USARTx instance.
2241 * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler
2242 * @param USARTx USART Instance
2243 * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31)
2245 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef
*USARTx
)
2247 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_PSC
));
2251 * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods
2252 * (GT[7:0] bits : Guard time value)
2253 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2254 * Smartcard feature is supported by the USARTx instance.
2255 * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime
2256 * @param USARTx USART Instance
2257 * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF
2260 __STATIC_INLINE
void LL_USART_SetSmartcardGuardTime(USART_TypeDef
*USARTx
, uint32_t GuardTime
)
2262 MODIFY_REG(USARTx
->GTPR
, (uint16_t)USART_GTPR_GT
, (uint16_t)(GuardTime
<< USART_GTPR_GT_Pos
));
2266 * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods
2267 * (GT[7:0] bits : Guard time value)
2268 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2269 * Smartcard feature is supported by the USARTx instance.
2270 * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime
2271 * @param USARTx USART Instance
2272 * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF)
2274 __STATIC_INLINE
uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef
*USARTx
)
2276 return (uint32_t)(READ_BIT(USARTx
->GTPR
, USART_GTPR_GT
) >> USART_GTPR_GT_Pos
);
2283 /** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature
2288 * @brief Enable Single Wire Half-Duplex mode
2289 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2290 * Half-Duplex mode is supported by the USARTx instance.
2291 * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex
2292 * @param USARTx USART Instance
2295 __STATIC_INLINE
void LL_USART_EnableHalfDuplex(USART_TypeDef
*USARTx
)
2297 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
2301 * @brief Disable Single Wire Half-Duplex mode
2302 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2303 * Half-Duplex mode is supported by the USARTx instance.
2304 * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex
2305 * @param USARTx USART Instance
2308 __STATIC_INLINE
void LL_USART_DisableHalfDuplex(USART_TypeDef
*USARTx
)
2310 CLEAR_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
2314 * @brief Indicate if Single Wire Half-Duplex mode is enabled
2315 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2316 * Half-Duplex mode is supported by the USARTx instance.
2317 * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex
2318 * @param USARTx USART Instance
2319 * @retval State of bit (1 or 0).
2321 __STATIC_INLINE
uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef
*USARTx
)
2323 return ((READ_BIT(USARTx
->CR3
, USART_CR3_HDSEL
) == (USART_CR3_HDSEL
)) ? 1UL : 0UL);
2330 /** @defgroup USART_LL_EF_Configuration_SPI_SLAVE Configuration functions related to SPI Slave feature
2334 * @brief Enable SPI Synchronous Slave mode
2335 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2336 * SPI Slave mode feature is supported by the USARTx instance.
2337 * @rmtoll CR2 SLVEN LL_USART_EnableSPISlave
2338 * @param USARTx USART Instance
2341 __STATIC_INLINE
void LL_USART_EnableSPISlave(USART_TypeDef
*USARTx
)
2343 SET_BIT(USARTx
->CR2
, USART_CR2_SLVEN
);
2347 * @brief Disable SPI Synchronous Slave mode
2348 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2349 * SPI Slave mode feature is supported by the USARTx instance.
2350 * @rmtoll CR2 SLVEN LL_USART_DisableSPISlave
2351 * @param USARTx USART Instance
2354 __STATIC_INLINE
void LL_USART_DisableSPISlave(USART_TypeDef
*USARTx
)
2356 CLEAR_BIT(USARTx
->CR2
, USART_CR2_SLVEN
);
2360 * @brief Indicate if SPI Synchronous Slave mode is enabled
2361 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2362 * SPI Slave mode feature is supported by the USARTx instance.
2363 * @rmtoll CR2 SLVEN LL_USART_IsEnabledSPISlave
2364 * @param USARTx USART Instance
2365 * @retval State of bit (1 or 0).
2367 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSPISlave(USART_TypeDef
*USARTx
)
2369 return ((READ_BIT(USARTx
->CR2
, USART_CR2_SLVEN
) == (USART_CR2_SLVEN
)) ? 1UL : 0UL);
2373 * @brief Enable SPI Slave Selection using NSS input pin
2374 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2375 * SPI Slave mode feature is supported by the USARTx instance.
2376 * @note SPI Slave Selection depends on NSS input pin
2377 * (The slave is selected when NSS is low and deselected when NSS is high).
2378 * @rmtoll CR2 DIS_NSS LL_USART_EnableSPISlaveSelect
2379 * @param USARTx USART Instance
2382 __STATIC_INLINE
void LL_USART_EnableSPISlaveSelect(USART_TypeDef
*USARTx
)
2384 CLEAR_BIT(USARTx
->CR2
, USART_CR2_DIS_NSS
);
2388 * @brief Disable SPI Slave Selection using NSS input pin
2389 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2390 * SPI Slave mode feature is supported by the USARTx instance.
2391 * @note SPI Slave will be always selected and NSS input pin will be ignored.
2392 * @rmtoll CR2 DIS_NSS LL_USART_DisableSPISlaveSelect
2393 * @param USARTx USART Instance
2396 __STATIC_INLINE
void LL_USART_DisableSPISlaveSelect(USART_TypeDef
*USARTx
)
2398 SET_BIT(USARTx
->CR2
, USART_CR2_DIS_NSS
);
2402 * @brief Indicate if SPI Slave Selection depends on NSS input pin
2403 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
2404 * SPI Slave mode feature is supported by the USARTx instance.
2405 * @rmtoll CR2 DIS_NSS LL_USART_IsEnabledSPISlaveSelect
2406 * @param USARTx USART Instance
2407 * @retval State of bit (1 or 0).
2409 __STATIC_INLINE
uint32_t LL_USART_IsEnabledSPISlaveSelect(USART_TypeDef
*USARTx
)
2411 return ((READ_BIT(USARTx
->CR2
, USART_CR2_DIS_NSS
) != (USART_CR2_DIS_NSS
)) ? 1UL : 0UL);
2418 /** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature
2423 * @brief Set LIN Break Detection Length
2424 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2425 * LIN feature is supported by the USARTx instance.
2426 * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen
2427 * @param USARTx USART Instance
2428 * @param LINBDLength This parameter can be one of the following values:
2429 * @arg @ref LL_USART_LINBREAK_DETECT_10B
2430 * @arg @ref LL_USART_LINBREAK_DETECT_11B
2433 __STATIC_INLINE
void LL_USART_SetLINBrkDetectionLen(USART_TypeDef
*USARTx
, uint32_t LINBDLength
)
2435 MODIFY_REG(USARTx
->CR2
, USART_CR2_LBDL
, LINBDLength
);
2439 * @brief Return LIN Break Detection Length
2440 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2441 * LIN feature is supported by the USARTx instance.
2442 * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen
2443 * @param USARTx USART Instance
2444 * @retval Returned value can be one of the following values:
2445 * @arg @ref LL_USART_LINBREAK_DETECT_10B
2446 * @arg @ref LL_USART_LINBREAK_DETECT_11B
2448 __STATIC_INLINE
uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef
*USARTx
)
2450 return (uint32_t)(READ_BIT(USARTx
->CR2
, USART_CR2_LBDL
));
2454 * @brief Enable LIN mode
2455 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2456 * LIN feature is supported by the USARTx instance.
2457 * @rmtoll CR2 LINEN LL_USART_EnableLIN
2458 * @param USARTx USART Instance
2461 __STATIC_INLINE
void LL_USART_EnableLIN(USART_TypeDef
*USARTx
)
2463 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
2467 * @brief Disable LIN mode
2468 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2469 * LIN feature is supported by the USARTx instance.
2470 * @rmtoll CR2 LINEN LL_USART_DisableLIN
2471 * @param USARTx USART Instance
2474 __STATIC_INLINE
void LL_USART_DisableLIN(USART_TypeDef
*USARTx
)
2476 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
2480 * @brief Indicate if LIN mode is enabled
2481 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2482 * LIN feature is supported by the USARTx instance.
2483 * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN
2484 * @param USARTx USART Instance
2485 * @retval State of bit (1 or 0).
2487 __STATIC_INLINE
uint32_t LL_USART_IsEnabledLIN(USART_TypeDef
*USARTx
)
2489 return ((READ_BIT(USARTx
->CR2
, USART_CR2_LINEN
) == (USART_CR2_LINEN
)) ? 1UL : 0UL);
2496 /** @defgroup USART_LL_EF_Configuration_DE Configuration functions related to Driver Enable feature
2501 * @brief Set DEDT (Driver Enable De-Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2502 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2503 * Driver Enable feature is supported by the USARTx instance.
2504 * @rmtoll CR1 DEDT LL_USART_SetDEDeassertionTime
2505 * @param USARTx USART Instance
2506 * @param Time Value between Min_Data=0 and Max_Data=31
2509 __STATIC_INLINE
void LL_USART_SetDEDeassertionTime(USART_TypeDef
*USARTx
, uint32_t Time
)
2511 MODIFY_REG(USARTx
->CR1
, USART_CR1_DEDT
, Time
<< USART_CR1_DEDT_Pos
);
2515 * @brief Return DEDT (Driver Enable De-Assertion Time)
2516 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2517 * Driver Enable feature is supported by the USARTx instance.
2518 * @rmtoll CR1 DEDT LL_USART_GetDEDeassertionTime
2519 * @param USARTx USART Instance
2520 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2522 __STATIC_INLINE
uint32_t LL_USART_GetDEDeassertionTime(USART_TypeDef
*USARTx
)
2524 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_DEDT
) >> USART_CR1_DEDT_Pos
);
2528 * @brief Set DEAT (Driver Enable Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2529 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2530 * Driver Enable feature is supported by the USARTx instance.
2531 * @rmtoll CR1 DEAT LL_USART_SetDEAssertionTime
2532 * @param USARTx USART Instance
2533 * @param Time Value between Min_Data=0 and Max_Data=31
2536 __STATIC_INLINE
void LL_USART_SetDEAssertionTime(USART_TypeDef
*USARTx
, uint32_t Time
)
2538 MODIFY_REG(USARTx
->CR1
, USART_CR1_DEAT
, Time
<< USART_CR1_DEAT_Pos
);
2542 * @brief Return DEAT (Driver Enable Assertion Time)
2543 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2544 * Driver Enable feature is supported by the USARTx instance.
2545 * @rmtoll CR1 DEAT LL_USART_GetDEAssertionTime
2546 * @param USARTx USART Instance
2547 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2549 __STATIC_INLINE
uint32_t LL_USART_GetDEAssertionTime(USART_TypeDef
*USARTx
)
2551 return (uint32_t)(READ_BIT(USARTx
->CR1
, USART_CR1_DEAT
) >> USART_CR1_DEAT_Pos
);
2555 * @brief Enable Driver Enable (DE) Mode
2556 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2557 * Driver Enable feature is supported by the USARTx instance.
2558 * @rmtoll CR3 DEM LL_USART_EnableDEMode
2559 * @param USARTx USART Instance
2562 __STATIC_INLINE
void LL_USART_EnableDEMode(USART_TypeDef
*USARTx
)
2564 SET_BIT(USARTx
->CR3
, USART_CR3_DEM
);
2568 * @brief Disable Driver Enable (DE) Mode
2569 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2570 * Driver Enable feature is supported by the USARTx instance.
2571 * @rmtoll CR3 DEM LL_USART_DisableDEMode
2572 * @param USARTx USART Instance
2575 __STATIC_INLINE
void LL_USART_DisableDEMode(USART_TypeDef
*USARTx
)
2577 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DEM
);
2581 * @brief Indicate if Driver Enable (DE) Mode is enabled
2582 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2583 * Driver Enable feature is supported by the USARTx instance.
2584 * @rmtoll CR3 DEM LL_USART_IsEnabledDEMode
2585 * @param USARTx USART Instance
2586 * @retval State of bit (1 or 0).
2588 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDEMode(USART_TypeDef
*USARTx
)
2590 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DEM
) == (USART_CR3_DEM
)) ? 1UL : 0UL);
2594 * @brief Select Driver Enable Polarity
2595 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2596 * Driver Enable feature is supported by the USARTx instance.
2597 * @rmtoll CR3 DEP LL_USART_SetDESignalPolarity
2598 * @param USARTx USART Instance
2599 * @param Polarity This parameter can be one of the following values:
2600 * @arg @ref LL_USART_DE_POLARITY_HIGH
2601 * @arg @ref LL_USART_DE_POLARITY_LOW
2604 __STATIC_INLINE
void LL_USART_SetDESignalPolarity(USART_TypeDef
*USARTx
, uint32_t Polarity
)
2606 MODIFY_REG(USARTx
->CR3
, USART_CR3_DEP
, Polarity
);
2610 * @brief Return Driver Enable Polarity
2611 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2612 * Driver Enable feature is supported by the USARTx instance.
2613 * @rmtoll CR3 DEP LL_USART_GetDESignalPolarity
2614 * @param USARTx USART Instance
2615 * @retval Returned value can be one of the following values:
2616 * @arg @ref LL_USART_DE_POLARITY_HIGH
2617 * @arg @ref LL_USART_DE_POLARITY_LOW
2619 __STATIC_INLINE
uint32_t LL_USART_GetDESignalPolarity(USART_TypeDef
*USARTx
)
2621 return (uint32_t)(READ_BIT(USARTx
->CR3
, USART_CR3_DEP
));
2628 /** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services
2633 * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART)
2634 * @note In UART mode, the following bits must be kept cleared:
2635 * - LINEN bit in the USART_CR2 register,
2636 * - CLKEN bit in the USART_CR2 register,
2637 * - SCEN bit in the USART_CR3 register,
2638 * - IREN bit in the USART_CR3 register,
2639 * - HDSEL bit in the USART_CR3 register.
2640 * @note Call of this function is equivalent to following function call sequence :
2641 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2642 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2643 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2644 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2645 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2646 * @note Other remaining configurations items related to Asynchronous Mode
2647 * (as Baud Rate, Word length, Parity, ...) should be set using
2648 * dedicated functions
2649 * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n
2650 * CR2 CLKEN LL_USART_ConfigAsyncMode\n
2651 * CR3 SCEN LL_USART_ConfigAsyncMode\n
2652 * CR3 IREN LL_USART_ConfigAsyncMode\n
2653 * CR3 HDSEL LL_USART_ConfigAsyncMode
2654 * @param USARTx USART Instance
2657 __STATIC_INLINE
void LL_USART_ConfigAsyncMode(USART_TypeDef
*USARTx
)
2659 /* In Asynchronous mode, the following bits must be kept cleared:
2660 - LINEN, CLKEN bits in the USART_CR2 register,
2661 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2662 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2663 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
2667 * @brief Perform basic configuration of USART for enabling use in Synchronous Mode
2668 * @note In Synchronous mode, the following bits must be kept cleared:
2669 * - LINEN bit in the USART_CR2 register,
2670 * - SCEN bit in the USART_CR3 register,
2671 * - IREN bit in the USART_CR3 register,
2672 * - HDSEL bit in the USART_CR3 register.
2673 * This function also sets the USART in Synchronous mode.
2674 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
2675 * Synchronous mode is supported by the USARTx instance.
2676 * @note Call of this function is equivalent to following function call sequence :
2677 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2678 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2679 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2680 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2681 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2682 * @note Other remaining configurations items related to Synchronous Mode
2683 * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using
2684 * dedicated functions
2685 * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n
2686 * CR2 CLKEN LL_USART_ConfigSyncMode\n
2687 * CR3 SCEN LL_USART_ConfigSyncMode\n
2688 * CR3 IREN LL_USART_ConfigSyncMode\n
2689 * CR3 HDSEL LL_USART_ConfigSyncMode
2690 * @param USARTx USART Instance
2693 __STATIC_INLINE
void LL_USART_ConfigSyncMode(USART_TypeDef
*USARTx
)
2695 /* In Synchronous mode, the following bits must be kept cleared:
2696 - LINEN bit in the USART_CR2 register,
2697 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2698 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
2699 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
| USART_CR3_HDSEL
));
2700 /* set the UART/USART in Synchronous mode */
2701 SET_BIT(USARTx
->CR2
, USART_CR2_CLKEN
);
2705 * @brief Perform basic configuration of USART for enabling use in LIN Mode
2706 * @note In LIN mode, the following bits must be kept cleared:
2707 * - STOP and CLKEN bits in the USART_CR2 register,
2708 * - SCEN bit in the USART_CR3 register,
2709 * - IREN bit in the USART_CR3 register,
2710 * - HDSEL bit in the USART_CR3 register.
2711 * This function also set the UART/USART in LIN mode.
2712 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2713 * LIN feature is supported by the USARTx instance.
2714 * @note Call of this function is equivalent to following function call sequence :
2715 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2716 * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2717 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2718 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2719 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2720 * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function
2721 * @note Other remaining configurations items related to LIN Mode
2722 * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using
2723 * dedicated functions
2724 * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n
2725 * CR2 STOP LL_USART_ConfigLINMode\n
2726 * CR2 LINEN LL_USART_ConfigLINMode\n
2727 * CR3 IREN LL_USART_ConfigLINMode\n
2728 * CR3 SCEN LL_USART_ConfigLINMode\n
2729 * CR3 HDSEL LL_USART_ConfigLINMode
2730 * @param USARTx USART Instance
2733 __STATIC_INLINE
void LL_USART_ConfigLINMode(USART_TypeDef
*USARTx
)
2735 /* In LIN mode, the following bits must be kept cleared:
2736 - STOP and CLKEN bits in the USART_CR2 register,
2737 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2738 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_CLKEN
| USART_CR2_STOP
));
2739 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_SCEN
| USART_CR3_HDSEL
));
2740 /* Set the UART/USART in LIN mode */
2741 SET_BIT(USARTx
->CR2
, USART_CR2_LINEN
);
2745 * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode
2746 * @note In Half Duplex mode, the following bits must be kept cleared:
2747 * - LINEN bit in the USART_CR2 register,
2748 * - CLKEN bit in the USART_CR2 register,
2749 * - SCEN bit in the USART_CR3 register,
2750 * - IREN bit in the USART_CR3 register,
2751 * This function also sets the UART/USART in Half Duplex mode.
2752 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2753 * Half-Duplex mode is supported by the USARTx instance.
2754 * @note Call of this function is equivalent to following function call sequence :
2755 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2756 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2757 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2758 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2759 * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function
2760 * @note Other remaining configurations items related to Half Duplex Mode
2761 * (as Baud Rate, Word length, Parity, ...) should be set using
2762 * dedicated functions
2763 * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n
2764 * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n
2765 * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n
2766 * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n
2767 * CR3 IREN LL_USART_ConfigHalfDuplexMode
2768 * @param USARTx USART Instance
2771 __STATIC_INLINE
void LL_USART_ConfigHalfDuplexMode(USART_TypeDef
*USARTx
)
2773 /* In Half Duplex mode, the following bits must be kept cleared:
2774 - LINEN and CLKEN bits in the USART_CR2 register,
2775 - SCEN and IREN bits in the USART_CR3 register.*/
2776 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2777 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_IREN
));
2778 /* set the UART/USART in Half Duplex mode */
2779 SET_BIT(USARTx
->CR3
, USART_CR3_HDSEL
);
2783 * @brief Perform basic configuration of USART for enabling use in Smartcard Mode
2784 * @note In Smartcard mode, the following bits must be kept cleared:
2785 * - LINEN bit in the USART_CR2 register,
2786 * - IREN bit in the USART_CR3 register,
2787 * - HDSEL bit in the USART_CR3 register.
2788 * This function also configures Stop bits to 1.5 bits and
2789 * sets the USART in Smartcard mode (SCEN bit).
2790 * Clock Output is also enabled (CLKEN).
2791 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2792 * Smartcard feature is supported by the USARTx instance.
2793 * @note Call of this function is equivalent to following function call sequence :
2794 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2795 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2796 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2797 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2798 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2799 * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function
2800 * @note Other remaining configurations items related to Smartcard Mode
2801 * (as Baud Rate, Word length, Parity, ...) should be set using
2802 * dedicated functions
2803 * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n
2804 * CR2 STOP LL_USART_ConfigSmartcardMode\n
2805 * CR2 CLKEN LL_USART_ConfigSmartcardMode\n
2806 * CR3 HDSEL LL_USART_ConfigSmartcardMode\n
2807 * CR3 SCEN LL_USART_ConfigSmartcardMode
2808 * @param USARTx USART Instance
2811 __STATIC_INLINE
void LL_USART_ConfigSmartcardMode(USART_TypeDef
*USARTx
)
2813 /* In Smartcard mode, the following bits must be kept cleared:
2814 - LINEN bit in the USART_CR2 register,
2815 - IREN and HDSEL bits in the USART_CR3 register.*/
2816 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
));
2817 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_IREN
| USART_CR3_HDSEL
));
2818 /* Configure Stop bits to 1.5 bits */
2819 /* Synchronous mode is activated by default */
2820 SET_BIT(USARTx
->CR2
, (USART_CR2_STOP_0
| USART_CR2_STOP_1
| USART_CR2_CLKEN
));
2821 /* set the UART/USART in Smartcard mode */
2822 SET_BIT(USARTx
->CR3
, USART_CR3_SCEN
);
2826 * @brief Perform basic configuration of USART for enabling use in Irda Mode
2827 * @note In IRDA mode, the following bits must be kept cleared:
2828 * - LINEN bit in the USART_CR2 register,
2829 * - STOP and CLKEN bits in the USART_CR2 register,
2830 * - SCEN bit in the USART_CR3 register,
2831 * - HDSEL bit in the USART_CR3 register.
2832 * This function also sets the UART/USART in IRDA mode (IREN bit).
2833 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2834 * IrDA feature is supported by the USARTx instance.
2835 * @note Call of this function is equivalent to following function call sequence :
2836 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2837 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2838 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2839 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2840 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2841 * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function
2842 * @note Other remaining configurations items related to Irda Mode
2843 * (as Baud Rate, Word length, Power mode, ...) should be set using
2844 * dedicated functions
2845 * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n
2846 * CR2 CLKEN LL_USART_ConfigIrdaMode\n
2847 * CR2 STOP LL_USART_ConfigIrdaMode\n
2848 * CR3 SCEN LL_USART_ConfigIrdaMode\n
2849 * CR3 HDSEL LL_USART_ConfigIrdaMode\n
2850 * CR3 IREN LL_USART_ConfigIrdaMode
2851 * @param USARTx USART Instance
2854 __STATIC_INLINE
void LL_USART_ConfigIrdaMode(USART_TypeDef
*USARTx
)
2856 /* In IRDA mode, the following bits must be kept cleared:
2857 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
2858 - SCEN and HDSEL bits in the USART_CR3 register.*/
2859 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
| USART_CR2_STOP
));
2860 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
));
2861 /* set the UART/USART in IRDA mode */
2862 SET_BIT(USARTx
->CR3
, USART_CR3_IREN
);
2866 * @brief Perform basic configuration of USART for enabling use in Multi processor Mode
2867 * (several USARTs connected in a network, one of the USARTs can be the master,
2868 * its TX output connected to the RX inputs of the other slaves USARTs).
2869 * @note In MultiProcessor mode, the following bits must be kept cleared:
2870 * - LINEN bit in the USART_CR2 register,
2871 * - CLKEN bit in the USART_CR2 register,
2872 * - SCEN bit in the USART_CR3 register,
2873 * - IREN bit in the USART_CR3 register,
2874 * - HDSEL bit in the USART_CR3 register.
2875 * @note Call of this function is equivalent to following function call sequence :
2876 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2877 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2878 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2879 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2880 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2881 * @note Other remaining configurations items related to Multi processor Mode
2882 * (as Baud Rate, Wake Up Method, Node address, ...) should be set using
2883 * dedicated functions
2884 * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n
2885 * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n
2886 * CR3 SCEN LL_USART_ConfigMultiProcessMode\n
2887 * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n
2888 * CR3 IREN LL_USART_ConfigMultiProcessMode
2889 * @param USARTx USART Instance
2892 __STATIC_INLINE
void LL_USART_ConfigMultiProcessMode(USART_TypeDef
*USARTx
)
2894 /* In Multi Processor mode, the following bits must be kept cleared:
2895 - LINEN and CLKEN bits in the USART_CR2 register,
2896 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2897 CLEAR_BIT(USARTx
->CR2
, (USART_CR2_LINEN
| USART_CR2_CLKEN
));
2898 CLEAR_BIT(USARTx
->CR3
, (USART_CR3_SCEN
| USART_CR3_HDSEL
| USART_CR3_IREN
));
2905 /** @defgroup USART_LL_EF_FLAG_Management FLAG_Management
2910 * @brief Check if the USART Parity Error Flag is set or not
2911 * @rmtoll ISR PE LL_USART_IsActiveFlag_PE
2912 * @param USARTx USART Instance
2913 * @retval State of bit (1 or 0).
2915 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef
*USARTx
)
2917 return ((READ_BIT(USARTx
->ISR
, USART_ISR_PE
) == (USART_ISR_PE
)) ? 1UL : 0UL);
2921 * @brief Check if the USART Framing Error Flag is set or not
2922 * @rmtoll ISR FE LL_USART_IsActiveFlag_FE
2923 * @param USARTx USART Instance
2924 * @retval State of bit (1 or 0).
2926 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef
*USARTx
)
2928 return ((READ_BIT(USARTx
->ISR
, USART_ISR_FE
) == (USART_ISR_FE
)) ? 1UL : 0UL);
2932 * @brief Check if the USART Noise error detected Flag is set or not
2933 * @rmtoll ISR NE LL_USART_IsActiveFlag_NE
2934 * @param USARTx USART Instance
2935 * @retval State of bit (1 or 0).
2937 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef
*USARTx
)
2939 return ((READ_BIT(USARTx
->ISR
, USART_ISR_NE
) == (USART_ISR_NE
)) ? 1UL : 0UL);
2943 * @brief Check if the USART OverRun Error Flag is set or not
2944 * @rmtoll ISR ORE LL_USART_IsActiveFlag_ORE
2945 * @param USARTx USART Instance
2946 * @retval State of bit (1 or 0).
2948 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef
*USARTx
)
2950 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ORE
) == (USART_ISR_ORE
)) ? 1UL : 0UL);
2954 * @brief Check if the USART IDLE line detected Flag is set or not
2955 * @rmtoll ISR IDLE LL_USART_IsActiveFlag_IDLE
2956 * @param USARTx USART Instance
2957 * @retval State of bit (1 or 0).
2959 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef
*USARTx
)
2961 return ((READ_BIT(USARTx
->ISR
, USART_ISR_IDLE
) == (USART_ISR_IDLE
)) ? 1UL : 0UL);
2965 #define LL_USART_IsActiveFlag_RXNE LL_USART_IsActiveFlag_RXNE_RXFNE
2968 * @brief Check if the USART Read Data Register or USART RX FIFO Not Empty Flag is set or not
2969 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
2970 * FIFO mode feature is supported by the USARTx instance.
2971 * @rmtoll ISR RXNE_RXFNE LL_USART_IsActiveFlag_RXNE_RXFNE
2972 * @param USARTx USART Instance
2973 * @retval State of bit (1 or 0).
2975 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RXNE_RXFNE(USART_TypeDef
*USARTx
)
2977 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RXNE_RXFNE
) == (USART_ISR_RXNE_RXFNE
)) ? 1UL : 0UL);
2981 * @brief Check if the USART Transmission Complete Flag is set or not
2982 * @rmtoll ISR TC LL_USART_IsActiveFlag_TC
2983 * @param USARTx USART Instance
2984 * @retval State of bit (1 or 0).
2986 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef
*USARTx
)
2988 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TC
) == (USART_ISR_TC
)) ? 1UL : 0UL);
2992 #define LL_USART_IsActiveFlag_TXE LL_USART_IsActiveFlag_TXE_TXFNF
2995 * @brief Check if the USART Transmit Data Register Empty or USART TX FIFO Not Full Flag is set or not
2996 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
2997 * FIFO mode feature is supported by the USARTx instance.
2998 * @rmtoll ISR TXE_TXFNF LL_USART_IsActiveFlag_TXE_TXFNF
2999 * @param USARTx USART Instance
3000 * @retval State of bit (1 or 0).
3002 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TXE_TXFNF(USART_TypeDef
*USARTx
)
3004 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TXE_TXFNF
) == (USART_ISR_TXE_TXFNF
)) ? 1UL : 0UL);
3008 * @brief Check if the USART LIN Break Detection Flag is set or not
3009 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3010 * LIN feature is supported by the USARTx instance.
3011 * @rmtoll ISR LBDF LL_USART_IsActiveFlag_LBD
3012 * @param USARTx USART Instance
3013 * @retval State of bit (1 or 0).
3015 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef
*USARTx
)
3017 return ((READ_BIT(USARTx
->ISR
, USART_ISR_LBDF
) == (USART_ISR_LBDF
)) ? 1UL : 0UL);
3021 * @brief Check if the USART CTS interrupt Flag is set or not
3022 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3023 * Hardware Flow control feature is supported by the USARTx instance.
3024 * @rmtoll ISR CTSIF LL_USART_IsActiveFlag_nCTS
3025 * @param USARTx USART Instance
3026 * @retval State of bit (1 or 0).
3028 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef
*USARTx
)
3030 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CTSIF
) == (USART_ISR_CTSIF
)) ? 1UL : 0UL);
3034 * @brief Check if the USART CTS Flag is set or not
3035 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3036 * Hardware Flow control feature is supported by the USARTx instance.
3037 * @rmtoll ISR CTS LL_USART_IsActiveFlag_CTS
3038 * @param USARTx USART Instance
3039 * @retval State of bit (1 or 0).
3041 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_CTS(USART_TypeDef
*USARTx
)
3043 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CTS
) == (USART_ISR_CTS
)) ? 1UL : 0UL);
3047 * @brief Check if the USART Receiver Time Out Flag is set or not
3048 * @rmtoll ISR RTOF LL_USART_IsActiveFlag_RTO
3049 * @param USARTx USART Instance
3050 * @retval State of bit (1 or 0).
3052 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RTO(USART_TypeDef
*USARTx
)
3054 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RTOF
) == (USART_ISR_RTOF
)) ? 1UL : 0UL);
3058 * @brief Check if the USART End Of Block Flag is set or not
3059 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3060 * Smartcard feature is supported by the USARTx instance.
3061 * @rmtoll ISR EOBF LL_USART_IsActiveFlag_EOB
3062 * @param USARTx USART Instance
3063 * @retval State of bit (1 or 0).
3065 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_EOB(USART_TypeDef
*USARTx
)
3067 return ((READ_BIT(USARTx
->ISR
, USART_ISR_EOBF
) == (USART_ISR_EOBF
)) ? 1UL : 0UL);
3071 * @brief Check if the SPI Slave Underrun error flag is set or not
3072 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
3073 * SPI Slave mode feature is supported by the USARTx instance.
3074 * @rmtoll ISR UDR LL_USART_IsActiveFlag_UDR
3075 * @param USARTx USART Instance
3076 * @retval State of bit (1 or 0).
3078 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_UDR(USART_TypeDef
*USARTx
)
3080 return ((READ_BIT(USARTx
->ISR
, USART_ISR_UDR
) == (USART_ISR_UDR
)) ? 1UL : 0UL);
3084 * @brief Check if the USART Auto-Baud Rate Error Flag is set or not
3085 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
3086 * Auto Baud Rate detection feature is supported by the USARTx instance.
3087 * @rmtoll ISR ABRE LL_USART_IsActiveFlag_ABRE
3088 * @param USARTx USART Instance
3089 * @retval State of bit (1 or 0).
3091 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ABRE(USART_TypeDef
*USARTx
)
3093 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ABRE
) == (USART_ISR_ABRE
)) ? 1UL : 0UL);
3097 * @brief Check if the USART Auto-Baud Rate Flag is set or not
3098 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
3099 * Auto Baud Rate detection feature is supported by the USARTx instance.
3100 * @rmtoll ISR ABRF LL_USART_IsActiveFlag_ABR
3101 * @param USARTx USART Instance
3102 * @retval State of bit (1 or 0).
3104 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_ABR(USART_TypeDef
*USARTx
)
3106 return ((READ_BIT(USARTx
->ISR
, USART_ISR_ABRF
) == (USART_ISR_ABRF
)) ? 1UL : 0UL);
3110 * @brief Check if the USART Busy Flag is set or not
3111 * @rmtoll ISR BUSY LL_USART_IsActiveFlag_BUSY
3112 * @param USARTx USART Instance
3113 * @retval State of bit (1 or 0).
3115 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_BUSY(USART_TypeDef
*USARTx
)
3117 return ((READ_BIT(USARTx
->ISR
, USART_ISR_BUSY
) == (USART_ISR_BUSY
)) ? 1UL : 0UL);
3121 * @brief Check if the USART Character Match Flag is set or not
3122 * @rmtoll ISR CMF LL_USART_IsActiveFlag_CM
3123 * @param USARTx USART Instance
3124 * @retval State of bit (1 or 0).
3126 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_CM(USART_TypeDef
*USARTx
)
3128 return ((READ_BIT(USARTx
->ISR
, USART_ISR_CMF
) == (USART_ISR_CMF
)) ? 1UL : 0UL);
3132 * @brief Check if the USART Send Break Flag is set or not
3133 * @rmtoll ISR SBKF LL_USART_IsActiveFlag_SBK
3134 * @param USARTx USART Instance
3135 * @retval State of bit (1 or 0).
3137 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef
*USARTx
)
3139 return ((READ_BIT(USARTx
->ISR
, USART_ISR_SBKF
) == (USART_ISR_SBKF
)) ? 1UL : 0UL);
3143 * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not
3144 * @rmtoll ISR RWU LL_USART_IsActiveFlag_RWU
3145 * @param USARTx USART Instance
3146 * @retval State of bit (1 or 0).
3148 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef
*USARTx
)
3150 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RWU
) == (USART_ISR_RWU
)) ? 1UL : 0UL);
3154 * @brief Check if the USART Wake Up from stop mode Flag is set or not
3155 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3156 * Wake-up from Stop mode feature is supported by the USARTx instance.
3157 * @rmtoll ISR WUF LL_USART_IsActiveFlag_WKUP
3158 * @param USARTx USART Instance
3159 * @retval State of bit (1 or 0).
3161 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_WKUP(USART_TypeDef
*USARTx
)
3163 return ((READ_BIT(USARTx
->ISR
, USART_ISR_WUF
) == (USART_ISR_WUF
)) ? 1UL : 0UL);
3167 * @brief Check if the USART Transmit Enable Acknowledge Flag is set or not
3168 * @rmtoll ISR TEACK LL_USART_IsActiveFlag_TEACK
3169 * @param USARTx USART Instance
3170 * @retval State of bit (1 or 0).
3172 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TEACK(USART_TypeDef
*USARTx
)
3174 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TEACK
) == (USART_ISR_TEACK
)) ? 1UL : 0UL);
3178 * @brief Check if the USART Receive Enable Acknowledge Flag is set or not
3179 * @rmtoll ISR REACK LL_USART_IsActiveFlag_REACK
3180 * @param USARTx USART Instance
3181 * @retval State of bit (1 or 0).
3183 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_REACK(USART_TypeDef
*USARTx
)
3185 return ((READ_BIT(USARTx
->ISR
, USART_ISR_REACK
) == (USART_ISR_REACK
)) ? 1UL : 0UL);
3189 * @brief Check if the USART TX FIFO Empty Flag is set or not
3190 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3191 * FIFO mode feature is supported by the USARTx instance.
3192 * @rmtoll ISR TXFE LL_USART_IsActiveFlag_TXFE
3193 * @param USARTx USART Instance
3194 * @retval State of bit (1 or 0).
3196 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TXFE(USART_TypeDef
*USARTx
)
3198 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TXFE
) == (USART_ISR_TXFE
)) ? 1UL : 0UL);
3202 * @brief Check if the USART RX FIFO Full Flag is set or not
3203 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3204 * FIFO mode feature is supported by the USARTx instance.
3205 * @rmtoll ISR RXFF LL_USART_IsActiveFlag_RXFF
3206 * @param USARTx USART Instance
3207 * @retval State of bit (1 or 0).
3209 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RXFF(USART_TypeDef
*USARTx
)
3211 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RXFF
) == (USART_ISR_RXFF
)) ? 1UL : 0UL);
3215 * @brief Check if the Smartcard Transmission Complete Before Guard Time Flag is set or not
3216 * @rmtoll ISR TCBGT LL_USART_IsActiveFlag_TCBGT
3217 * @param USARTx USART Instance
3218 * @retval State of bit (1 or 0).
3220 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TCBGT(USART_TypeDef
*USARTx
)
3222 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TCBGT
) == (USART_ISR_TCBGT
)) ? 1UL : 0UL);
3226 * @brief Check if the USART TX FIFO Threshold Flag is set or not
3227 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3228 * FIFO mode feature is supported by the USARTx instance.
3229 * @rmtoll ISR TXFT LL_USART_IsActiveFlag_TXFT
3230 * @param USARTx USART Instance
3231 * @retval State of bit (1 or 0).
3233 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_TXFT(USART_TypeDef
*USARTx
)
3235 return ((READ_BIT(USARTx
->ISR
, USART_ISR_TXFT
) == (USART_ISR_TXFT
)) ? 1UL : 0UL);
3239 * @brief Check if the USART RX FIFO Threshold Flag is set or not
3240 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3241 * FIFO mode feature is supported by the USARTx instance.
3242 * @rmtoll ISR RXFT LL_USART_IsActiveFlag_RXFT
3243 * @param USARTx USART Instance
3244 * @retval State of bit (1 or 0).
3246 __STATIC_INLINE
uint32_t LL_USART_IsActiveFlag_RXFT(USART_TypeDef
*USARTx
)
3248 return ((READ_BIT(USARTx
->ISR
, USART_ISR_RXFT
) == (USART_ISR_RXFT
)) ? 1UL : 0UL);
3252 * @brief Clear Parity Error Flag
3253 * @rmtoll ICR PECF LL_USART_ClearFlag_PE
3254 * @param USARTx USART Instance
3257 __STATIC_INLINE
void LL_USART_ClearFlag_PE(USART_TypeDef
*USARTx
)
3259 WRITE_REG(USARTx
->ICR
, USART_ICR_PECF
);
3263 * @brief Clear Framing Error Flag
3264 * @rmtoll ICR FECF LL_USART_ClearFlag_FE
3265 * @param USARTx USART Instance
3268 __STATIC_INLINE
void LL_USART_ClearFlag_FE(USART_TypeDef
*USARTx
)
3270 WRITE_REG(USARTx
->ICR
, USART_ICR_FECF
);
3274 * @brief Clear Noise Error detected Flag
3275 * @rmtoll ICR NECF LL_USART_ClearFlag_NE
3276 * @param USARTx USART Instance
3279 __STATIC_INLINE
void LL_USART_ClearFlag_NE(USART_TypeDef
*USARTx
)
3281 WRITE_REG(USARTx
->ICR
, USART_ICR_NECF
);
3285 * @brief Clear OverRun Error Flag
3286 * @rmtoll ICR ORECF LL_USART_ClearFlag_ORE
3287 * @param USARTx USART Instance
3290 __STATIC_INLINE
void LL_USART_ClearFlag_ORE(USART_TypeDef
*USARTx
)
3292 WRITE_REG(USARTx
->ICR
, USART_ICR_ORECF
);
3296 * @brief Clear IDLE line detected Flag
3297 * @rmtoll ICR IDLECF LL_USART_ClearFlag_IDLE
3298 * @param USARTx USART Instance
3301 __STATIC_INLINE
void LL_USART_ClearFlag_IDLE(USART_TypeDef
*USARTx
)
3303 WRITE_REG(USARTx
->ICR
, USART_ICR_IDLECF
);
3307 * @brief Clear TX FIFO Empty Flag
3308 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3309 * FIFO mode feature is supported by the USARTx instance.
3310 * @rmtoll ICR TXFECF LL_USART_ClearFlag_TXFE
3311 * @param USARTx USART Instance
3314 __STATIC_INLINE
void LL_USART_ClearFlag_TXFE(USART_TypeDef
*USARTx
)
3316 WRITE_REG(USARTx
->ICR
, USART_ICR_TXFECF
);
3320 * @brief Clear Transmission Complete Flag
3321 * @rmtoll ICR TCCF LL_USART_ClearFlag_TC
3322 * @param USARTx USART Instance
3325 __STATIC_INLINE
void LL_USART_ClearFlag_TC(USART_TypeDef
*USARTx
)
3327 WRITE_REG(USARTx
->ICR
, USART_ICR_TCCF
);
3331 * @brief Clear Smartcard Transmission Complete Before Guard Time Flag
3332 * @rmtoll ICR TCBGTCF LL_USART_ClearFlag_TCBGT
3333 * @param USARTx USART Instance
3336 __STATIC_INLINE
void LL_USART_ClearFlag_TCBGT(USART_TypeDef
*USARTx
)
3338 WRITE_REG(USARTx
->ICR
, USART_ICR_TCBGTCF
);
3342 * @brief Clear LIN Break Detection Flag
3343 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3344 * LIN feature is supported by the USARTx instance.
3345 * @rmtoll ICR LBDCF LL_USART_ClearFlag_LBD
3346 * @param USARTx USART Instance
3349 __STATIC_INLINE
void LL_USART_ClearFlag_LBD(USART_TypeDef
*USARTx
)
3351 WRITE_REG(USARTx
->ICR
, USART_ICR_LBDCF
);
3355 * @brief Clear CTS Interrupt Flag
3356 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3357 * Hardware Flow control feature is supported by the USARTx instance.
3358 * @rmtoll ICR CTSCF LL_USART_ClearFlag_nCTS
3359 * @param USARTx USART Instance
3362 __STATIC_INLINE
void LL_USART_ClearFlag_nCTS(USART_TypeDef
*USARTx
)
3364 WRITE_REG(USARTx
->ICR
, USART_ICR_CTSCF
);
3368 * @brief Clear Receiver Time Out Flag
3369 * @rmtoll ICR RTOCF LL_USART_ClearFlag_RTO
3370 * @param USARTx USART Instance
3373 __STATIC_INLINE
void LL_USART_ClearFlag_RTO(USART_TypeDef
*USARTx
)
3375 WRITE_REG(USARTx
->ICR
, USART_ICR_RTOCF
);
3379 * @brief Clear End Of Block Flag
3380 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3381 * Smartcard feature is supported by the USARTx instance.
3382 * @rmtoll ICR EOBCF LL_USART_ClearFlag_EOB
3383 * @param USARTx USART Instance
3386 __STATIC_INLINE
void LL_USART_ClearFlag_EOB(USART_TypeDef
*USARTx
)
3388 WRITE_REG(USARTx
->ICR
, USART_ICR_EOBCF
);
3392 * @brief Clear SPI Slave Underrun Flag
3393 * @note Macro @ref IS_UART_SPI_SLAVE_INSTANCE(USARTx) can be used to check whether or not
3394 * SPI Slave mode feature is supported by the USARTx instance.
3395 * @rmtoll ICR UDRCF LL_USART_ClearFlag_UDR
3396 * @param USARTx USART Instance
3399 __STATIC_INLINE
void LL_USART_ClearFlag_UDR(USART_TypeDef
*USARTx
)
3401 WRITE_REG(USARTx
->ICR
, USART_ICR_UDRCF
);
3405 * @brief Clear Character Match Flag
3406 * @rmtoll ICR CMCF LL_USART_ClearFlag_CM
3407 * @param USARTx USART Instance
3410 __STATIC_INLINE
void LL_USART_ClearFlag_CM(USART_TypeDef
*USARTx
)
3412 WRITE_REG(USARTx
->ICR
, USART_ICR_CMCF
);
3416 * @brief Clear Wake Up from stop mode Flag
3417 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3418 * Wake-up from Stop mode feature is supported by the USARTx instance.
3419 * @rmtoll ICR WUCF LL_USART_ClearFlag_WKUP
3420 * @param USARTx USART Instance
3423 __STATIC_INLINE
void LL_USART_ClearFlag_WKUP(USART_TypeDef
*USARTx
)
3425 WRITE_REG(USARTx
->ICR
, USART_ICR_WUCF
);
3432 /** @defgroup USART_LL_EF_IT_Management IT_Management
3437 * @brief Enable IDLE Interrupt
3438 * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE
3439 * @param USARTx USART Instance
3442 __STATIC_INLINE
void LL_USART_EnableIT_IDLE(USART_TypeDef
*USARTx
)
3444 SET_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
3448 #define LL_USART_EnableIT_RXNE LL_USART_EnableIT_RXNE_RXFNE
3451 * @brief Enable RX Not Empty and RX FIFO Not Empty Interrupt
3452 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3453 * FIFO mode feature is supported by the USARTx instance.
3454 * @rmtoll CR1 RXNEIE_RXFNEIE LL_USART_EnableIT_RXNE_RXFNE
3455 * @param USARTx USART Instance
3458 __STATIC_INLINE
void LL_USART_EnableIT_RXNE_RXFNE(USART_TypeDef
*USARTx
)
3460 SET_BIT(USARTx
->CR1
, USART_CR1_RXNEIE_RXFNEIE
);
3464 * @brief Enable Transmission Complete Interrupt
3465 * @rmtoll CR1 TCIE LL_USART_EnableIT_TC
3466 * @param USARTx USART Instance
3469 __STATIC_INLINE
void LL_USART_EnableIT_TC(USART_TypeDef
*USARTx
)
3471 SET_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
3475 #define LL_USART_EnableIT_TXE LL_USART_EnableIT_TXE_TXFNF
3478 * @brief Enable TX Empty and TX FIFO Not Full Interrupt
3479 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3480 * FIFO mode feature is supported by the USARTx instance.
3481 * @rmtoll CR1 TXEIE_TXFNFIE LL_USART_EnableIT_TXE_TXFNF
3482 * @param USARTx USART Instance
3485 __STATIC_INLINE
void LL_USART_EnableIT_TXE_TXFNF(USART_TypeDef
*USARTx
)
3487 SET_BIT(USARTx
->CR1
, USART_CR1_TXEIE_TXFNFIE
);
3491 * @brief Enable Parity Error Interrupt
3492 * @rmtoll CR1 PEIE LL_USART_EnableIT_PE
3493 * @param USARTx USART Instance
3496 __STATIC_INLINE
void LL_USART_EnableIT_PE(USART_TypeDef
*USARTx
)
3498 SET_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
3502 * @brief Enable Character Match Interrupt
3503 * @rmtoll CR1 CMIE LL_USART_EnableIT_CM
3504 * @param USARTx USART Instance
3507 __STATIC_INLINE
void LL_USART_EnableIT_CM(USART_TypeDef
*USARTx
)
3509 SET_BIT(USARTx
->CR1
, USART_CR1_CMIE
);
3513 * @brief Enable Receiver Timeout Interrupt
3514 * @rmtoll CR1 RTOIE LL_USART_EnableIT_RTO
3515 * @param USARTx USART Instance
3518 __STATIC_INLINE
void LL_USART_EnableIT_RTO(USART_TypeDef
*USARTx
)
3520 SET_BIT(USARTx
->CR1
, USART_CR1_RTOIE
);
3524 * @brief Enable End Of Block Interrupt
3525 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3526 * Smartcard feature is supported by the USARTx instance.
3527 * @rmtoll CR1 EOBIE LL_USART_EnableIT_EOB
3528 * @param USARTx USART Instance
3531 __STATIC_INLINE
void LL_USART_EnableIT_EOB(USART_TypeDef
*USARTx
)
3533 SET_BIT(USARTx
->CR1
, USART_CR1_EOBIE
);
3537 * @brief Enable TX FIFO Empty Interrupt
3538 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3539 * FIFO mode feature is supported by the USARTx instance.
3540 * @rmtoll CR1 TXFEIE LL_USART_EnableIT_TXFE
3541 * @param USARTx USART Instance
3544 __STATIC_INLINE
void LL_USART_EnableIT_TXFE(USART_TypeDef
*USARTx
)
3546 SET_BIT(USARTx
->CR1
, USART_CR1_TXFEIE
);
3550 * @brief Enable RX FIFO Full Interrupt
3551 * @rmtoll CR1 RXFFIE LL_USART_EnableIT_RXFF
3552 * @param USARTx USART Instance
3555 __STATIC_INLINE
void LL_USART_EnableIT_RXFF(USART_TypeDef
*USARTx
)
3557 SET_BIT(USARTx
->CR1
, USART_CR1_RXFFIE
);
3561 * @brief Enable LIN Break Detection Interrupt
3562 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3563 * LIN feature is supported by the USARTx instance.
3564 * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD
3565 * @param USARTx USART Instance
3568 __STATIC_INLINE
void LL_USART_EnableIT_LBD(USART_TypeDef
*USARTx
)
3570 SET_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
3574 * @brief Enable Error Interrupt
3575 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3576 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3577 * 0: Interrupt is inhibited
3578 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3579 * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR
3580 * @param USARTx USART Instance
3583 __STATIC_INLINE
void LL_USART_EnableIT_ERROR(USART_TypeDef
*USARTx
)
3585 SET_BIT(USARTx
->CR3
, USART_CR3_EIE
);
3589 * @brief Enable CTS Interrupt
3590 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3591 * Hardware Flow control feature is supported by the USARTx instance.
3592 * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS
3593 * @param USARTx USART Instance
3596 __STATIC_INLINE
void LL_USART_EnableIT_CTS(USART_TypeDef
*USARTx
)
3598 SET_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
3602 * @brief Enable Wake Up from Stop Mode Interrupt
3603 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3604 * Wake-up from Stop mode feature is supported by the USARTx instance.
3605 * @rmtoll CR3 WUFIE LL_USART_EnableIT_WKUP
3606 * @param USARTx USART Instance
3609 __STATIC_INLINE
void LL_USART_EnableIT_WKUP(USART_TypeDef
*USARTx
)
3611 SET_BIT(USARTx
->CR3
, USART_CR3_WUFIE
);
3615 * @brief Enable TX FIFO Threshold Interrupt
3616 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3617 * FIFO mode feature is supported by the USARTx instance.
3618 * @rmtoll CR3 TXFTIE LL_USART_EnableIT_TXFT
3619 * @param USARTx USART Instance
3622 __STATIC_INLINE
void LL_USART_EnableIT_TXFT(USART_TypeDef
*USARTx
)
3624 SET_BIT(USARTx
->CR3
, USART_CR3_TXFTIE
);
3628 * @brief Enable Smartcard Transmission Complete Before Guard Time Interrupt
3629 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3630 * Smartcard feature is supported by the USARTx instance.
3631 * @rmtoll CR3 TCBGTIE LL_USART_EnableIT_TCBGT
3632 * @param USARTx USART Instance
3635 __STATIC_INLINE
void LL_USART_EnableIT_TCBGT(USART_TypeDef
*USARTx
)
3637 SET_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
);
3641 * @brief Enable RX FIFO Threshold Interrupt
3642 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3643 * FIFO mode feature is supported by the USARTx instance.
3644 * @rmtoll CR3 RXFTIE LL_USART_EnableIT_RXFT
3645 * @param USARTx USART Instance
3648 __STATIC_INLINE
void LL_USART_EnableIT_RXFT(USART_TypeDef
*USARTx
)
3650 SET_BIT(USARTx
->CR3
, USART_CR3_RXFTIE
);
3654 * @brief Disable IDLE Interrupt
3655 * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE
3656 * @param USARTx USART Instance
3659 __STATIC_INLINE
void LL_USART_DisableIT_IDLE(USART_TypeDef
*USARTx
)
3661 CLEAR_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
);
3665 #define LL_USART_DisableIT_RXNE LL_USART_DisableIT_RXNE_RXFNE
3668 * @brief Disable RX Not Empty and RX FIFO Not Empty Interrupt
3669 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3670 * FIFO mode feature is supported by the USARTx instance.
3671 * @rmtoll CR1 RXNEIE_RXFNEIE LL_USART_DisableIT_RXNE_RXFNE
3672 * @param USARTx USART Instance
3675 __STATIC_INLINE
void LL_USART_DisableIT_RXNE_RXFNE(USART_TypeDef
*USARTx
)
3677 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RXNEIE_RXFNEIE
);
3681 * @brief Disable Transmission Complete Interrupt
3682 * @rmtoll CR1 TCIE LL_USART_DisableIT_TC
3683 * @param USARTx USART Instance
3686 __STATIC_INLINE
void LL_USART_DisableIT_TC(USART_TypeDef
*USARTx
)
3688 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TCIE
);
3692 #define LL_USART_DisableIT_TXE LL_USART_DisableIT_TXE_TXFNF
3695 * @brief Disable TX Empty and TX FIFO Not Full Interrupt
3696 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3697 * FIFO mode feature is supported by the USARTx instance.
3698 * @rmtoll CR1 TXEIE_TXFNFIE LL_USART_DisableIT_TXE_TXFNF
3699 * @param USARTx USART Instance
3702 __STATIC_INLINE
void LL_USART_DisableIT_TXE_TXFNF(USART_TypeDef
*USARTx
)
3704 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TXEIE_TXFNFIE
);
3708 * @brief Disable Parity Error Interrupt
3709 * @rmtoll CR1 PEIE LL_USART_DisableIT_PE
3710 * @param USARTx USART Instance
3713 __STATIC_INLINE
void LL_USART_DisableIT_PE(USART_TypeDef
*USARTx
)
3715 CLEAR_BIT(USARTx
->CR1
, USART_CR1_PEIE
);
3719 * @brief Disable Character Match Interrupt
3720 * @rmtoll CR1 CMIE LL_USART_DisableIT_CM
3721 * @param USARTx USART Instance
3724 __STATIC_INLINE
void LL_USART_DisableIT_CM(USART_TypeDef
*USARTx
)
3726 CLEAR_BIT(USARTx
->CR1
, USART_CR1_CMIE
);
3730 * @brief Disable Receiver Timeout Interrupt
3731 * @rmtoll CR1 RTOIE LL_USART_DisableIT_RTO
3732 * @param USARTx USART Instance
3735 __STATIC_INLINE
void LL_USART_DisableIT_RTO(USART_TypeDef
*USARTx
)
3737 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RTOIE
);
3741 * @brief Disable End Of Block Interrupt
3742 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3743 * Smartcard feature is supported by the USARTx instance.
3744 * @rmtoll CR1 EOBIE LL_USART_DisableIT_EOB
3745 * @param USARTx USART Instance
3748 __STATIC_INLINE
void LL_USART_DisableIT_EOB(USART_TypeDef
*USARTx
)
3750 CLEAR_BIT(USARTx
->CR1
, USART_CR1_EOBIE
);
3754 * @brief Disable TX FIFO Empty Interrupt
3755 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3756 * FIFO mode feature is supported by the USARTx instance.
3757 * @rmtoll CR1 TXFEIE LL_USART_DisableIT_TXFE
3758 * @param USARTx USART Instance
3761 __STATIC_INLINE
void LL_USART_DisableIT_TXFE(USART_TypeDef
*USARTx
)
3763 CLEAR_BIT(USARTx
->CR1
, USART_CR1_TXFEIE
);
3767 * @brief Disable RX FIFO Full Interrupt
3768 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3769 * FIFO mode feature is supported by the USARTx instance.
3770 * @rmtoll CR1 RXFFIE LL_USART_DisableIT_RXFF
3771 * @param USARTx USART Instance
3774 __STATIC_INLINE
void LL_USART_DisableIT_RXFF(USART_TypeDef
*USARTx
)
3776 CLEAR_BIT(USARTx
->CR1
, USART_CR1_RXFFIE
);
3780 * @brief Disable LIN Break Detection Interrupt
3781 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3782 * LIN feature is supported by the USARTx instance.
3783 * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD
3784 * @param USARTx USART Instance
3787 __STATIC_INLINE
void LL_USART_DisableIT_LBD(USART_TypeDef
*USARTx
)
3789 CLEAR_BIT(USARTx
->CR2
, USART_CR2_LBDIE
);
3793 * @brief Disable Error Interrupt
3794 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3795 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3796 * 0: Interrupt is inhibited
3797 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3798 * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR
3799 * @param USARTx USART Instance
3802 __STATIC_INLINE
void LL_USART_DisableIT_ERROR(USART_TypeDef
*USARTx
)
3804 CLEAR_BIT(USARTx
->CR3
, USART_CR3_EIE
);
3808 * @brief Disable CTS Interrupt
3809 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3810 * Hardware Flow control feature is supported by the USARTx instance.
3811 * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS
3812 * @param USARTx USART Instance
3815 __STATIC_INLINE
void LL_USART_DisableIT_CTS(USART_TypeDef
*USARTx
)
3817 CLEAR_BIT(USARTx
->CR3
, USART_CR3_CTSIE
);
3821 * @brief Disable Wake Up from Stop Mode Interrupt
3822 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3823 * Wake-up from Stop mode feature is supported by the USARTx instance.
3824 * @rmtoll CR3 WUFIE LL_USART_DisableIT_WKUP
3825 * @param USARTx USART Instance
3828 __STATIC_INLINE
void LL_USART_DisableIT_WKUP(USART_TypeDef
*USARTx
)
3830 CLEAR_BIT(USARTx
->CR3
, USART_CR3_WUFIE
);
3834 * @brief Disable TX FIFO Threshold Interrupt
3835 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3836 * FIFO mode feature is supported by the USARTx instance.
3837 * @rmtoll CR3 TXFTIE LL_USART_DisableIT_TXFT
3838 * @param USARTx USART Instance
3841 __STATIC_INLINE
void LL_USART_DisableIT_TXFT(USART_TypeDef
*USARTx
)
3843 CLEAR_BIT(USARTx
->CR3
, USART_CR3_TXFTIE
);
3847 * @brief Disable Smartcard Transmission Complete Before Guard Time Interrupt
3848 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3849 * Smartcard feature is supported by the USARTx instance.
3850 * @rmtoll CR3 TCBGTIE LL_USART_DisableIT_TCBGT
3851 * @param USARTx USART Instance
3854 __STATIC_INLINE
void LL_USART_DisableIT_TCBGT(USART_TypeDef
*USARTx
)
3856 CLEAR_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
);
3860 * @brief Disable RX FIFO Threshold Interrupt
3861 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3862 * FIFO mode feature is supported by the USARTx instance.
3863 * @rmtoll CR3 RXFTIE LL_USART_DisableIT_RXFT
3864 * @param USARTx USART Instance
3867 __STATIC_INLINE
void LL_USART_DisableIT_RXFT(USART_TypeDef
*USARTx
)
3869 CLEAR_BIT(USARTx
->CR3
, USART_CR3_RXFTIE
);
3873 * @brief Check if the USART IDLE Interrupt source is enabled or disabled.
3874 * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE
3875 * @param USARTx USART Instance
3876 * @retval State of bit (1 or 0).
3878 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef
*USARTx
)
3880 return ((READ_BIT(USARTx
->CR1
, USART_CR1_IDLEIE
) == (USART_CR1_IDLEIE
)) ? 1UL : 0UL);
3884 #define LL_USART_IsEnabledIT_RXNE LL_USART_IsEnabledIT_RXNE_RXFNE
3887 * @brief Check if the USART RX Not Empty and USART RX FIFO Not Empty Interrupt is enabled or disabled.
3888 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3889 * FIFO mode feature is supported by the USARTx instance.
3890 * @rmtoll CR1 RXNEIE_RXFNEIE LL_USART_IsEnabledIT_RXNE_RXFNE
3891 * @param USARTx USART Instance
3892 * @retval State of bit (1 or 0).
3894 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RXNE_RXFNE(USART_TypeDef
*USARTx
)
3896 return ((READ_BIT(USARTx
->CR1
, USART_CR1_RXNEIE_RXFNEIE
) == (USART_CR1_RXNEIE_RXFNEIE
)) ? 1UL : 0UL);
3900 * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled.
3901 * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC
3902 * @param USARTx USART Instance
3903 * @retval State of bit (1 or 0).
3905 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef
*USARTx
)
3907 return ((READ_BIT(USARTx
->CR1
, USART_CR1_TCIE
) == (USART_CR1_TCIE
)) ? 1UL : 0UL);
3911 #define LL_USART_IsEnabledIT_TXE LL_USART_IsEnabledIT_TXE_TXFNF
3914 * @brief Check if the USART TX Empty and USART TX FIFO Not Full Interrupt is enabled or disabled
3915 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3916 * FIFO mode feature is supported by the USARTx instance.
3917 * @rmtoll CR1 TXEIE_TXFNFIE LL_USART_IsEnabledIT_TXE_TXFNF
3918 * @param USARTx USART Instance
3919 * @retval State of bit (1 or 0).
3921 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TXE_TXFNF(USART_TypeDef
*USARTx
)
3923 return ((READ_BIT(USARTx
->CR1
, USART_CR1_TXEIE_TXFNFIE
) == (USART_CR1_TXEIE_TXFNFIE
)) ? 1UL : 0UL);
3927 * @brief Check if the USART Parity Error Interrupt is enabled or disabled.
3928 * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE
3929 * @param USARTx USART Instance
3930 * @retval State of bit (1 or 0).
3932 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef
*USARTx
)
3934 return ((READ_BIT(USARTx
->CR1
, USART_CR1_PEIE
) == (USART_CR1_PEIE
)) ? 1UL : 0UL);
3938 * @brief Check if the USART Character Match Interrupt is enabled or disabled.
3939 * @rmtoll CR1 CMIE LL_USART_IsEnabledIT_CM
3940 * @param USARTx USART Instance
3941 * @retval State of bit (1 or 0).
3943 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_CM(USART_TypeDef
*USARTx
)
3945 return ((READ_BIT(USARTx
->CR1
, USART_CR1_CMIE
) == (USART_CR1_CMIE
)) ? 1UL : 0UL);
3949 * @brief Check if the USART Receiver Timeout Interrupt is enabled or disabled.
3950 * @rmtoll CR1 RTOIE LL_USART_IsEnabledIT_RTO
3951 * @param USARTx USART Instance
3952 * @retval State of bit (1 or 0).
3954 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RTO(USART_TypeDef
*USARTx
)
3956 return ((READ_BIT(USARTx
->CR1
, USART_CR1_RTOIE
) == (USART_CR1_RTOIE
)) ? 1UL : 0UL);
3960 * @brief Check if the USART End Of Block Interrupt is enabled or disabled.
3961 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3962 * Smartcard feature is supported by the USARTx instance.
3963 * @rmtoll CR1 EOBIE LL_USART_IsEnabledIT_EOB
3964 * @param USARTx USART Instance
3965 * @retval State of bit (1 or 0).
3967 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_EOB(USART_TypeDef
*USARTx
)
3969 return ((READ_BIT(USARTx
->CR1
, USART_CR1_EOBIE
) == (USART_CR1_EOBIE
)) ? 1UL : 0UL);
3973 * @brief Check if the USART TX FIFO Empty Interrupt is enabled or disabled
3974 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3975 * FIFO mode feature is supported by the USARTx instance.
3976 * @rmtoll CR1 TXFEIE LL_USART_IsEnabledIT_TXFE
3977 * @param USARTx USART Instance
3978 * @retval State of bit (1 or 0).
3980 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TXFE(USART_TypeDef
*USARTx
)
3982 return ((READ_BIT(USARTx
->CR1
, USART_CR1_TXFEIE
) == (USART_CR1_TXFEIE
)) ? 1UL : 0UL);
3986 * @brief Check if the USART RX FIFO Full Interrupt is enabled or disabled
3987 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
3988 * FIFO mode feature is supported by the USARTx instance.
3989 * @rmtoll CR1 RXFFIE LL_USART_IsEnabledIT_RXFF
3990 * @param USARTx USART Instance
3991 * @retval State of bit (1 or 0).
3993 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RXFF(USART_TypeDef
*USARTx
)
3995 return ((READ_BIT(USARTx
->CR1
, USART_CR1_RXFFIE
) == (USART_CR1_RXFFIE
)) ? 1UL : 0UL);
3999 * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled.
4000 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
4001 * LIN feature is supported by the USARTx instance.
4002 * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD
4003 * @param USARTx USART Instance
4004 * @retval State of bit (1 or 0).
4006 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef
*USARTx
)
4008 return ((READ_BIT(USARTx
->CR2
, USART_CR2_LBDIE
) == (USART_CR2_LBDIE
)) ? 1UL : 0UL);
4012 * @brief Check if the USART Error Interrupt is enabled or disabled.
4013 * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR
4014 * @param USARTx USART Instance
4015 * @retval State of bit (1 or 0).
4017 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef
*USARTx
)
4019 return ((READ_BIT(USARTx
->CR3
, USART_CR3_EIE
) == (USART_CR3_EIE
)) ? 1UL : 0UL);
4023 * @brief Check if the USART CTS Interrupt is enabled or disabled.
4024 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
4025 * Hardware Flow control feature is supported by the USARTx instance.
4026 * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS
4027 * @param USARTx USART Instance
4028 * @retval State of bit (1 or 0).
4030 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef
*USARTx
)
4032 return ((READ_BIT(USARTx
->CR3
, USART_CR3_CTSIE
) == (USART_CR3_CTSIE
)) ? 1UL : 0UL);
4036 * @brief Check if the USART Wake Up from Stop Mode Interrupt is enabled or disabled.
4037 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
4038 * Wake-up from Stop mode feature is supported by the USARTx instance.
4039 * @rmtoll CR3 WUFIE LL_USART_IsEnabledIT_WKUP
4040 * @param USARTx USART Instance
4041 * @retval State of bit (1 or 0).
4043 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_WKUP(USART_TypeDef
*USARTx
)
4045 return ((READ_BIT(USARTx
->CR3
, USART_CR3_WUFIE
) == (USART_CR3_WUFIE
)) ? 1UL : 0UL);
4049 * @brief Check if USART TX FIFO Threshold Interrupt is enabled or disabled
4050 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
4051 * FIFO mode feature is supported by the USARTx instance.
4052 * @rmtoll CR3 TXFTIE LL_USART_IsEnabledIT_TXFT
4053 * @param USARTx USART Instance
4054 * @retval State of bit (1 or 0).
4056 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TXFT(USART_TypeDef
*USARTx
)
4058 return ((READ_BIT(USARTx
->CR3
, USART_CR3_TXFTIE
) == (USART_CR3_TXFTIE
)) ? 1UL : 0UL);
4062 * @brief Check if the Smartcard Transmission Complete Before Guard Time Interrupt is enabled or disabled.
4063 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
4064 * Smartcard feature is supported by the USARTx instance.
4065 * @rmtoll CR3 TCBGTIE LL_USART_IsEnabledIT_TCBGT
4066 * @param USARTx USART Instance
4067 * @retval State of bit (1 or 0).
4069 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_TCBGT(USART_TypeDef
*USARTx
)
4071 return ((READ_BIT(USARTx
->CR3
, USART_CR3_TCBGTIE
) == (USART_CR3_TCBGTIE
)) ? 1UL : 0UL);
4075 * @brief Check if USART RX FIFO Threshold Interrupt is enabled or disabled
4076 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
4077 * FIFO mode feature is supported by the USARTx instance.
4078 * @rmtoll CR3 RXFTIE LL_USART_IsEnabledIT_RXFT
4079 * @param USARTx USART Instance
4080 * @retval State of bit (1 or 0).
4082 __STATIC_INLINE
uint32_t LL_USART_IsEnabledIT_RXFT(USART_TypeDef
*USARTx
)
4084 return ((READ_BIT(USARTx
->CR3
, USART_CR3_RXFTIE
) == (USART_CR3_RXFTIE
)) ? 1UL : 0UL);
4091 /** @defgroup USART_LL_EF_DMA_Management DMA_Management
4096 * @brief Enable DMA Mode for reception
4097 * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX
4098 * @param USARTx USART Instance
4101 __STATIC_INLINE
void LL_USART_EnableDMAReq_RX(USART_TypeDef
*USARTx
)
4103 SET_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
4107 * @brief Disable DMA Mode for reception
4108 * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX
4109 * @param USARTx USART Instance
4112 __STATIC_INLINE
void LL_USART_DisableDMAReq_RX(USART_TypeDef
*USARTx
)
4114 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAR
);
4118 * @brief Check if DMA Mode is enabled for reception
4119 * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX
4120 * @param USARTx USART Instance
4121 * @retval State of bit (1 or 0).
4123 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef
*USARTx
)
4125 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DMAR
) == (USART_CR3_DMAR
)) ? 1UL : 0UL);
4129 * @brief Enable DMA Mode for transmission
4130 * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX
4131 * @param USARTx USART Instance
4134 __STATIC_INLINE
void LL_USART_EnableDMAReq_TX(USART_TypeDef
*USARTx
)
4136 SET_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
4140 * @brief Disable DMA Mode for transmission
4141 * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX
4142 * @param USARTx USART Instance
4145 __STATIC_INLINE
void LL_USART_DisableDMAReq_TX(USART_TypeDef
*USARTx
)
4147 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DMAT
);
4151 * @brief Check if DMA Mode is enabled for transmission
4152 * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX
4153 * @param USARTx USART Instance
4154 * @retval State of bit (1 or 0).
4156 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef
*USARTx
)
4158 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DMAT
) == (USART_CR3_DMAT
)) ? 1UL : 0UL);
4162 * @brief Enable DMA Disabling on Reception Error
4163 * @rmtoll CR3 DDRE LL_USART_EnableDMADeactOnRxErr
4164 * @param USARTx USART Instance
4167 __STATIC_INLINE
void LL_USART_EnableDMADeactOnRxErr(USART_TypeDef
*USARTx
)
4169 SET_BIT(USARTx
->CR3
, USART_CR3_DDRE
);
4173 * @brief Disable DMA Disabling on Reception Error
4174 * @rmtoll CR3 DDRE LL_USART_DisableDMADeactOnRxErr
4175 * @param USARTx USART Instance
4178 __STATIC_INLINE
void LL_USART_DisableDMADeactOnRxErr(USART_TypeDef
*USARTx
)
4180 CLEAR_BIT(USARTx
->CR3
, USART_CR3_DDRE
);
4184 * @brief Indicate if DMA Disabling on Reception Error is disabled
4185 * @rmtoll CR3 DDRE LL_USART_IsEnabledDMADeactOnRxErr
4186 * @param USARTx USART Instance
4187 * @retval State of bit (1 or 0).
4189 __STATIC_INLINE
uint32_t LL_USART_IsEnabledDMADeactOnRxErr(USART_TypeDef
*USARTx
)
4191 return ((READ_BIT(USARTx
->CR3
, USART_CR3_DDRE
) == (USART_CR3_DDRE
)) ? 1UL : 0UL);
4195 * @brief Get the data register address used for DMA transfer
4196 * @rmtoll RDR RDR LL_USART_DMA_GetRegAddr\n
4197 * @rmtoll TDR TDR LL_USART_DMA_GetRegAddr
4198 * @param USARTx USART Instance
4199 * @param Direction This parameter can be one of the following values:
4200 * @arg @ref LL_USART_DMA_REG_DATA_TRANSMIT
4201 * @arg @ref LL_USART_DMA_REG_DATA_RECEIVE
4202 * @retval Address of data register
4204 __STATIC_INLINE
uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef
*USARTx
, uint32_t Direction
)
4206 register uint32_t data_reg_addr
;
4208 if (Direction
== LL_USART_DMA_REG_DATA_TRANSMIT
)
4210 /* return address of TDR register */
4211 data_reg_addr
= (uint32_t) &(USARTx
->TDR
);
4215 /* return address of RDR register */
4216 data_reg_addr
= (uint32_t) &(USARTx
->RDR
);
4219 return data_reg_addr
;
4226 /** @defgroup USART_LL_EF_Data_Management Data_Management
4231 * @brief Read Receiver Data register (Receive Data value, 8 bits)
4232 * @rmtoll RDR RDR LL_USART_ReceiveData8
4233 * @param USARTx USART Instance
4234 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
4236 __STATIC_INLINE
uint8_t LL_USART_ReceiveData8(USART_TypeDef
*USARTx
)
4238 return (uint8_t)(READ_BIT(USARTx
->RDR
, USART_RDR_RDR
) & 0xFFU
);
4242 * @brief Read Receiver Data register (Receive Data value, 9 bits)
4243 * @rmtoll RDR RDR LL_USART_ReceiveData9
4244 * @param USARTx USART Instance
4245 * @retval Value between Min_Data=0x00 and Max_Data=0x1FF
4247 __STATIC_INLINE
uint16_t LL_USART_ReceiveData9(USART_TypeDef
*USARTx
)
4249 return (uint16_t)(READ_BIT(USARTx
->RDR
, USART_RDR_RDR
));
4253 * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits)
4254 * @rmtoll TDR TDR LL_USART_TransmitData8
4255 * @param USARTx USART Instance
4256 * @param Value between Min_Data=0x00 and Max_Data=0xFF
4259 __STATIC_INLINE
void LL_USART_TransmitData8(USART_TypeDef
*USARTx
, uint8_t Value
)
4261 USARTx
->TDR
= Value
;
4265 * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits)
4266 * @rmtoll TDR TDR LL_USART_TransmitData9
4267 * @param USARTx USART Instance
4268 * @param Value between Min_Data=0x00 and Max_Data=0x1FF
4271 __STATIC_INLINE
void LL_USART_TransmitData9(USART_TypeDef
*USARTx
, uint16_t Value
)
4273 USARTx
->TDR
= (uint16_t)(Value
& 0x1FFUL
);
4280 /** @defgroup USART_LL_EF_Execution Execution
4285 * @brief Request an Automatic Baud Rate measurement on next received data frame
4286 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
4287 * Auto Baud Rate detection feature is supported by the USARTx instance.
4288 * @rmtoll RQR ABRRQ LL_USART_RequestAutoBaudRate
4289 * @param USARTx USART Instance
4292 __STATIC_INLINE
void LL_USART_RequestAutoBaudRate(USART_TypeDef
*USARTx
)
4294 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_ABRRQ
);
4298 * @brief Request Break sending
4299 * @rmtoll RQR SBKRQ LL_USART_RequestBreakSending
4300 * @param USARTx USART Instance
4303 __STATIC_INLINE
void LL_USART_RequestBreakSending(USART_TypeDef
*USARTx
)
4305 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_SBKRQ
);
4309 * @brief Put USART in mute mode and set the RWU flag
4310 * @rmtoll RQR MMRQ LL_USART_RequestEnterMuteMode
4311 * @param USARTx USART Instance
4314 __STATIC_INLINE
void LL_USART_RequestEnterMuteMode(USART_TypeDef
*USARTx
)
4316 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_MMRQ
);
4320 * @brief Request a Receive Data and FIFO flush
4321 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
4322 * FIFO mode feature is supported by the USARTx instance.
4323 * @note Allows to discard the received data without reading them, and avoid an overrun
4325 * @rmtoll RQR RXFRQ LL_USART_RequestRxDataFlush
4326 * @param USARTx USART Instance
4329 __STATIC_INLINE
void LL_USART_RequestRxDataFlush(USART_TypeDef
*USARTx
)
4331 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_RXFRQ
);
4335 * @brief Request a Transmit data and FIFO flush
4336 * @note Macro @ref IS_UART_FIFO_INSTANCE(USARTx) can be used to check whether or not
4337 * FIFO mode feature is supported by the USARTx instance.
4338 * @rmtoll RQR TXFRQ LL_USART_RequestTxDataFlush
4339 * @param USARTx USART Instance
4342 __STATIC_INLINE
void LL_USART_RequestTxDataFlush(USART_TypeDef
*USARTx
)
4344 SET_BIT(USARTx
->RQR
, (uint16_t)USART_RQR_TXFRQ
);
4351 #if defined(USE_FULL_LL_DRIVER)
4352 /** @defgroup USART_LL_EF_Init Initialization and de-initialization functions
4355 ErrorStatus
LL_USART_DeInit(USART_TypeDef
*USARTx
);
4356 ErrorStatus
LL_USART_Init(USART_TypeDef
*USARTx
, LL_USART_InitTypeDef
*USART_InitStruct
);
4357 void LL_USART_StructInit(LL_USART_InitTypeDef
*USART_InitStruct
);
4358 ErrorStatus
LL_USART_ClockInit(USART_TypeDef
*USARTx
, LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
4359 void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef
*USART_ClockInitStruct
);
4363 #endif /* USE_FULL_LL_DRIVER */
4373 #endif /* USART1 || USART2 || USART3 || UART4 || UART5 */
4383 #endif /* STM32G4xx_LL_USART_H */
4385 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/