Updated and Validated
[betaflight.git] / lib / main / STM32F3 / Drivers / STM32F3xx_HAL_Driver / Inc / stm32f3xx_ll_usart.h
blob4886a23376f47edf3632195e10cc20f12cb9e058
1 /**
2 ******************************************************************************
3 * @file stm32f3xx_ll_usart.h
4 * @author MCD Application Team
5 * @brief Header file of USART LL module.
6 ******************************************************************************
7 * @attention
9 * <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
11 * Redistribution and use in source and binary forms, with or without modification,
12 * are permitted provided that the following conditions are met:
13 * 1. Redistributions of source code must retain the above copyright notice,
14 * this list of conditions and the following disclaimer.
15 * 2. Redistributions in binary form must reproduce the above copyright notice,
16 * this list of conditions and the following disclaimer in the documentation
17 * and/or other materials provided with the distribution.
18 * 3. Neither the name of STMicroelectronics nor the names of its contributors
19 * may be used to endorse or promote products derived from this software
20 * without specific prior written permission.
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33 ******************************************************************************
36 /* Define to prevent recursive inclusion -------------------------------------*/
37 #ifndef __STM32F3xx_LL_USART_H
38 #define __STM32F3xx_LL_USART_H
40 #ifdef __cplusplus
41 extern "C" {
42 #endif
44 /* Includes ------------------------------------------------------------------*/
45 #include "stm32f3xx.h"
47 /** @addtogroup STM32F3xx_LL_Driver
48 * @{
51 #if defined (USART1) || defined (USART2) || defined (USART3) || defined (UART4) || defined (UART5)
53 /** @defgroup USART_LL USART
54 * @{
57 /* Private types -------------------------------------------------------------*/
58 /* Private variables ---------------------------------------------------------*/
60 /* Private constants ---------------------------------------------------------*/
61 /** @defgroup USART_LL_Private_Constants USART Private Constants
62 * @{
64 /**
65 * @}
68 /* Private macros ------------------------------------------------------------*/
69 #if defined(USE_FULL_LL_DRIVER)
70 /** @defgroup USART_LL_Private_Macros USART Private Macros
71 * @{
73 /**
74 * @}
76 #endif /*USE_FULL_LL_DRIVER*/
78 /* Exported types ------------------------------------------------------------*/
79 #if defined(USE_FULL_LL_DRIVER)
80 /** @defgroup USART_LL_ES_INIT USART Exported Init structures
81 * @{
84 /**
85 * @brief LL USART Init Structure definition
87 typedef struct
89 uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate.
91 This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/
93 uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame.
94 This parameter can be a value of @ref USART_LL_EC_DATAWIDTH.
96 This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/
98 uint32_t StopBits; /*!< Specifies the number of stop bits transmitted.
99 This parameter can be a value of @ref USART_LL_EC_STOPBITS.
101 This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/
103 uint32_t Parity; /*!< Specifies the parity mode.
104 This parameter can be a value of @ref USART_LL_EC_PARITY.
106 This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/
108 uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled.
109 This parameter can be a value of @ref USART_LL_EC_DIRECTION.
111 This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/
113 uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled.
114 This parameter can be a value of @ref USART_LL_EC_HWCONTROL.
116 This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/
118 uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8.
119 This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING.
121 This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/
123 } LL_USART_InitTypeDef;
126 * @brief LL USART Clock Init Structure definition
128 typedef struct
130 uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled.
131 This parameter can be a value of @ref USART_LL_EC_CLOCK.
133 USART HW configuration can be modified afterwards using unitary functions
134 @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput().
135 For more details, refer to description of this function. */
137 uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock.
138 This parameter can be a value of @ref USART_LL_EC_POLARITY.
140 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity().
141 For more details, refer to description of this function. */
143 uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made.
144 This parameter can be a value of @ref USART_LL_EC_PHASE.
146 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase().
147 For more details, refer to description of this function. */
149 uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted
150 data bit (MSB) has to be output on the SCLK pin in synchronous mode.
151 This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE.
153 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput().
154 For more details, refer to description of this function. */
156 } LL_USART_ClockInitTypeDef;
159 * @}
161 #endif /* USE_FULL_LL_DRIVER */
163 /* Exported constants --------------------------------------------------------*/
164 /** @defgroup USART_LL_Exported_Constants USART Exported Constants
165 * @{
168 /** @defgroup USART_LL_EC_CLEAR_FLAG Clear Flags Defines
169 * @brief Flags defines which can be used with LL_USART_WriteReg function
170 * @{
172 #define LL_USART_ICR_PECF USART_ICR_PECF /*!< Parity error flag */
173 #define LL_USART_ICR_FECF USART_ICR_FECF /*!< Framing error flag */
174 #define LL_USART_ICR_NCF USART_ICR_NCF /*!< Noise detected flag */
175 #define LL_USART_ICR_ORECF USART_ICR_ORECF /*!< Overrun error flag */
176 #define LL_USART_ICR_IDLECF USART_ICR_IDLECF /*!< Idle line detected flag */
177 #define LL_USART_ICR_TCCF USART_ICR_TCCF /*!< Transmission complete flag */
178 #define LL_USART_ICR_LBDCF USART_ICR_LBDCF /*!< LIN break detection flag */
179 #define LL_USART_ICR_CTSCF USART_ICR_CTSCF /*!< CTS flag */
180 #define LL_USART_ICR_RTOCF USART_ICR_RTOCF /*!< Receiver timeout flag */
181 #define LL_USART_ICR_EOBCF USART_ICR_EOBCF /*!< End of block flag */
182 #define LL_USART_ICR_CMCF USART_ICR_CMCF /*!< Character match flag */
183 #define LL_USART_ICR_WUCF USART_ICR_WUCF /*!< Wakeup from Stop mode flag */
185 * @}
188 /** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines
189 * @brief Flags defines which can be used with LL_USART_ReadReg function
190 * @{
192 #define LL_USART_ISR_PE USART_ISR_PE /*!< Parity error flag */
193 #define LL_USART_ISR_FE USART_ISR_FE /*!< Framing error flag */
194 #define LL_USART_ISR_NE USART_ISR_NE /*!< Noise detected flag */
195 #define LL_USART_ISR_ORE USART_ISR_ORE /*!< Overrun error flag */
196 #define LL_USART_ISR_IDLE USART_ISR_IDLE /*!< Idle line detected flag */
197 #define LL_USART_ISR_RXNE USART_ISR_RXNE /*!< Read data register not empty flag */
198 #define LL_USART_ISR_TC USART_ISR_TC /*!< Transmission complete flag */
199 #define LL_USART_ISR_TXE USART_ISR_TXE /*!< Transmit data register empty flag */
200 #define LL_USART_ISR_LBDF USART_ISR_LBDF /*!< LIN break detection flag */
201 #define LL_USART_ISR_CTSIF USART_ISR_CTSIF /*!< CTS interrupt flag */
202 #define LL_USART_ISR_CTS USART_ISR_CTS /*!< CTS flag */
203 #define LL_USART_ISR_RTOF USART_ISR_RTOF /*!< Receiver timeout flag */
204 #define LL_USART_ISR_EOBF USART_ISR_EOBF /*!< End of block flag */
205 #define LL_USART_ISR_ABRE USART_ISR_ABRE /*!< Auto baud rate error flag */
206 #define LL_USART_ISR_ABRF USART_ISR_ABRF /*!< Auto baud rate flag */
207 #define LL_USART_ISR_BUSY USART_ISR_BUSY /*!< Busy flag */
208 #define LL_USART_ISR_CMF USART_ISR_CMF /*!< Character match flag */
209 #define LL_USART_ISR_SBKF USART_ISR_SBKF /*!< Send break flag */
210 #define LL_USART_ISR_RWU USART_ISR_RWU /*!< Receiver wakeup from Mute mode flag */
211 #define LL_USART_ISR_WUF USART_ISR_WUF /*!< Wakeup from Stop mode flag */
212 #define LL_USART_ISR_TEACK USART_ISR_TEACK /*!< Transmit enable acknowledge flag */
213 #define LL_USART_ISR_REACK USART_ISR_REACK /*!< Receive enable acknowledge flag */
215 * @}
218 /** @defgroup USART_LL_EC_IT IT Defines
219 * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions
220 * @{
222 #define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */
223 #define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */
224 #define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */
225 #define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */
226 #define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */
227 #define LL_USART_CR1_CMIE USART_CR1_CMIE /*!< Character match interrupt enable */
228 #define LL_USART_CR1_RTOIE USART_CR1_RTOIE /*!< Receiver timeout interrupt enable */
229 #define LL_USART_CR1_EOBIE USART_CR1_EOBIE /*!< End of Block interrupt enable */
230 #define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */
231 #define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */
232 #define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */
233 #define LL_USART_CR3_WUFIE USART_CR3_WUFIE /*!< Wakeup from Stop mode interrupt enable */
235 * @}
238 /** @defgroup USART_LL_EC_DIRECTION Communication Direction
239 * @{
241 #define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */
242 #define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */
243 #define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */
244 #define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */
246 * @}
249 /** @defgroup USART_LL_EC_PARITY Parity Control
250 * @{
252 #define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */
253 #define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */
254 #define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */
256 * @}
259 /** @defgroup USART_LL_EC_WAKEUP Wakeup
260 * @{
262 #define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */
263 #define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */
265 * @}
268 /** @defgroup USART_LL_EC_DATAWIDTH Datawidth
269 * @{
271 #if defined(USART_7BITS_SUPPORT)
272 #define LL_USART_DATAWIDTH_7B USART_CR1_M1 /*!< 7 bits word length : Start bit, 7 data bits, n stop bits */
273 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
274 #define LL_USART_DATAWIDTH_9B USART_CR1_M0 /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
275 #else
276 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
277 #define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
278 #endif
280 * @}
283 /** @defgroup USART_LL_EC_OVERSAMPLING Oversampling
284 * @{
286 #define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */
287 #define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */
289 * @}
292 #if defined(USE_FULL_LL_DRIVER)
293 /** @defgroup USART_LL_EC_CLOCK Clock Signal
294 * @{
297 #define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */
298 #define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */
300 * @}
302 #endif /*USE_FULL_LL_DRIVER*/
304 /** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse
305 * @{
307 #define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */
308 #define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */
310 * @}
313 /** @defgroup USART_LL_EC_PHASE Clock Phase
314 * @{
316 #define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */
317 #define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */
319 * @}
322 /** @defgroup USART_LL_EC_POLARITY Clock Polarity
323 * @{
325 #define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/
326 #define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */
328 * @}
331 /** @defgroup USART_LL_EC_STOPBITS Stop Bits
332 * @{
334 #define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */
335 #define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */
336 #define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */
337 #define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */
339 * @}
342 /** @defgroup USART_LL_EC_TXRX TX RX Pins Swap
343 * @{
345 #define LL_USART_TXRX_STANDARD 0x00000000U /*!< TX/RX pins are used as defined in standard pinout */
346 #define LL_USART_TXRX_SWAPPED (USART_CR2_SWAP) /*!< TX and RX pins functions are swapped. */
348 * @}
351 /** @defgroup USART_LL_EC_RXPIN_LEVEL RX Pin Active Level Inversion
352 * @{
354 #define LL_USART_RXPIN_LEVEL_STANDARD 0x00000000U /*!< RX pin signal works using the standard logic levels */
355 #define LL_USART_RXPIN_LEVEL_INVERTED (USART_CR2_RXINV) /*!< RX pin signal values are inverted. */
357 * @}
360 /** @defgroup USART_LL_EC_TXPIN_LEVEL TX Pin Active Level Inversion
361 * @{
363 #define LL_USART_TXPIN_LEVEL_STANDARD 0x00000000U /*!< TX pin signal works using the standard logic levels */
364 #define LL_USART_TXPIN_LEVEL_INVERTED (USART_CR2_TXINV) /*!< TX pin signal values are inverted. */
366 * @}
369 /** @defgroup USART_LL_EC_BINARY_LOGIC Binary Data Inversion
370 * @{
372 #define LL_USART_BINARY_LOGIC_POSITIVE 0x00000000U /*!< Logical data from the data register are send/received in positive/direct logic. (1=H, 0=L) */
373 #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. */
375 * @}
378 /** @defgroup USART_LL_EC_BITORDER Bit Order
379 * @{
381 #define LL_USART_BITORDER_LSBFIRST 0x00000000U /*!< data is transmitted/received with data bit 0 first, following the start bit */
382 #define LL_USART_BITORDER_MSBFIRST USART_CR2_MSBFIRST /*!< data is transmitted/received with the MSB first, following the start bit */
384 * @}
387 /** @defgroup USART_LL_EC_AUTOBAUD_DETECT_ON Autobaud Detection
388 * @{
390 #define LL_USART_AUTOBAUD_DETECT_ON_STARTBIT 0x00000000U /*!< Measurement of the start bit is used to detect the baud rate */
391 #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 */
392 #define LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME USART_CR2_ABRMODE_1 /*!< 0x7F frame detection */
393 #define LL_USART_AUTOBAUD_DETECT_ON_55_FRAME (USART_CR2_ABRMODE_1 | USART_CR2_ABRMODE_0) /*!< 0x55 frame detection */
395 * @}
398 /** @defgroup USART_LL_EC_ADDRESS_DETECT Address Length Detection
399 * @{
401 #define LL_USART_ADDRESS_DETECT_4B 0x00000000U /*!< 4-bit address detection method selected */
402 #define LL_USART_ADDRESS_DETECT_7B USART_CR2_ADDM7 /*!< 7-bit address detection (in 8-bit data mode) method selected */
404 * @}
407 /** @defgroup USART_LL_EC_HWCONTROL Hardware Control
408 * @{
410 #define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */
411 #define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */
412 #define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */
413 #define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */
415 * @}
418 /** @defgroup USART_LL_EC_WAKEUP_ON Wakeup Activation
419 * @{
421 #define LL_USART_WAKEUP_ON_ADDRESS 0x00000000U /*!< Wake up active on address match */
422 #define LL_USART_WAKEUP_ON_STARTBIT USART_CR3_WUS_1 /*!< Wake up active on Start bit detection */
423 #define LL_USART_WAKEUP_ON_RXNE (USART_CR3_WUS_0 | USART_CR3_WUS_1) /*!< Wake up active on RXNE */
425 * @}
428 /** @defgroup USART_LL_EC_IRDA_POWER IrDA Power
429 * @{
431 #define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */
432 #define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */
434 * @}
437 /** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length
438 * @{
440 #define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */
441 #define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */
443 * @}
446 /** @defgroup USART_LL_EC_DE_POLARITY Driver Enable Polarity
447 * @{
449 #define LL_USART_DE_POLARITY_HIGH 0x00000000U /*!< DE signal is active high */
450 #define LL_USART_DE_POLARITY_LOW USART_CR3_DEP /*!< DE signal is active low */
452 * @}
455 /** @defgroup USART_LL_EC_DMA_REG_DATA DMA Register Data
456 * @{
458 #define LL_USART_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for transmission */
459 #define LL_USART_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for reception */
461 * @}
465 * @}
468 /* Exported macro ------------------------------------------------------------*/
469 /** @defgroup USART_LL_Exported_Macros USART Exported Macros
470 * @{
473 /** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros
474 * @{
478 * @brief Write a value in USART register
479 * @param __INSTANCE__ USART Instance
480 * @param __REG__ Register to be written
481 * @param __VALUE__ Value to be written in the register
482 * @retval None
484 #define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
487 * @brief Read a value in USART register
488 * @param __INSTANCE__ USART Instance
489 * @param __REG__ Register to be read
490 * @retval Register value
492 #define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
494 * @}
497 /** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
498 * @{
502 * @brief Compute USARTDIV value according to Peripheral Clock and
503 * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned)
504 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
505 * @param __BAUDRATE__ Baud rate value to achieve
506 * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case
508 #define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__PERIPHCLK__)*2) + ((__BAUDRATE__)/2))/(__BAUDRATE__))
511 * @brief Compute USARTDIV value according to Peripheral Clock and
512 * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned)
513 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
514 * @param __BAUDRATE__ Baud rate value to achieve
515 * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case
517 #define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__PERIPHCLK__) + ((__BAUDRATE__)/2))/(__BAUDRATE__))
520 * @}
524 * @}
527 /* Exported functions --------------------------------------------------------*/
529 /** @defgroup USART_LL_Exported_Functions USART Exported Functions
530 * @{
533 /** @defgroup USART_LL_EF_Configuration Configuration functions
534 * @{
538 * @brief USART Enable
539 * @rmtoll CR1 UE LL_USART_Enable
540 * @param USARTx USART Instance
541 * @retval None
543 __STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx)
545 SET_BIT(USARTx->CR1, USART_CR1_UE);
549 * @brief USART Disable (all USART prescalers and outputs are disabled)
550 * @note When USART is disabled, USART prescalers and outputs are stopped immediately,
551 * and current operations are discarded. The configuration of the USART is kept, but all the status
552 * flags, in the USARTx_ISR are set to their default values.
553 * @rmtoll CR1 UE LL_USART_Disable
554 * @param USARTx USART Instance
555 * @retval None
557 __STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx)
559 CLEAR_BIT(USARTx->CR1, USART_CR1_UE);
563 * @brief Indicate if USART is enabled
564 * @rmtoll CR1 UE LL_USART_IsEnabled
565 * @param USARTx USART Instance
566 * @retval State of bit (1 or 0).
568 __STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx)
570 return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE));
574 * @brief USART enabled in STOP Mode.
575 * @note When this function is enabled, USART is able to wake up the MCU from Stop mode, provided that
576 * USART clock selection is HSI or LSE in RCC.
577 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
578 * Wake-up from Stop mode feature is supported by the USARTx instance.
579 * @rmtoll CR1 UESM LL_USART_EnableInStopMode
580 * @param USARTx USART Instance
581 * @retval None
583 __STATIC_INLINE void LL_USART_EnableInStopMode(USART_TypeDef *USARTx)
585 SET_BIT(USARTx->CR1, USART_CR1_UESM);
589 * @brief USART disabled in STOP Mode.
590 * @note When this function is disabled, USART is not able to wake up the MCU from Stop mode
591 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
592 * Wake-up from Stop mode feature is supported by the USARTx instance.
593 * @rmtoll CR1 UESM LL_USART_DisableInStopMode
594 * @param USARTx USART Instance
595 * @retval None
597 __STATIC_INLINE void LL_USART_DisableInStopMode(USART_TypeDef *USARTx)
599 CLEAR_BIT(USARTx->CR1, USART_CR1_UESM);
603 * @brief Indicate if USART is enabled in STOP Mode (able to wake up MCU from Stop mode or not)
604 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
605 * Wake-up from Stop mode feature is supported by the USARTx instance.
606 * @rmtoll CR1 UESM LL_USART_IsEnabledInStopMode
607 * @param USARTx USART Instance
608 * @retval State of bit (1 or 0).
610 __STATIC_INLINE uint32_t LL_USART_IsEnabledInStopMode(USART_TypeDef *USARTx)
612 return (READ_BIT(USARTx->CR1, USART_CR1_UESM) == (USART_CR1_UESM));
616 * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit)
617 * @rmtoll CR1 RE LL_USART_EnableDirectionRx
618 * @param USARTx USART Instance
619 * @retval None
621 __STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx)
623 SET_BIT(USARTx->CR1, USART_CR1_RE);
627 * @brief Receiver Disable
628 * @rmtoll CR1 RE LL_USART_DisableDirectionRx
629 * @param USARTx USART Instance
630 * @retval None
632 __STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx)
634 CLEAR_BIT(USARTx->CR1, USART_CR1_RE);
638 * @brief Transmitter Enable
639 * @rmtoll CR1 TE LL_USART_EnableDirectionTx
640 * @param USARTx USART Instance
641 * @retval None
643 __STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx)
645 SET_BIT(USARTx->CR1, USART_CR1_TE);
649 * @brief Transmitter Disable
650 * @rmtoll CR1 TE LL_USART_DisableDirectionTx
651 * @param USARTx USART Instance
652 * @retval None
654 __STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx)
656 CLEAR_BIT(USARTx->CR1, USART_CR1_TE);
660 * @brief Configure simultaneously enabled/disabled states
661 * of Transmitter and Receiver
662 * @rmtoll CR1 RE LL_USART_SetTransferDirection\n
663 * CR1 TE LL_USART_SetTransferDirection
664 * @param USARTx USART Instance
665 * @param TransferDirection This parameter can be one of the following values:
666 * @arg @ref LL_USART_DIRECTION_NONE
667 * @arg @ref LL_USART_DIRECTION_RX
668 * @arg @ref LL_USART_DIRECTION_TX
669 * @arg @ref LL_USART_DIRECTION_TX_RX
670 * @retval None
672 __STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection)
674 MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection);
678 * @brief Return enabled/disabled states of Transmitter and Receiver
679 * @rmtoll CR1 RE LL_USART_GetTransferDirection\n
680 * CR1 TE LL_USART_GetTransferDirection
681 * @param USARTx USART Instance
682 * @retval Returned value can be one of the following values:
683 * @arg @ref LL_USART_DIRECTION_NONE
684 * @arg @ref LL_USART_DIRECTION_RX
685 * @arg @ref LL_USART_DIRECTION_TX
686 * @arg @ref LL_USART_DIRECTION_TX_RX
688 __STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx)
690 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE));
694 * @brief Configure Parity (enabled/disabled and parity mode if enabled).
695 * @note This function selects if hardware parity control (generation and detection) is enabled or disabled.
696 * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position
697 * (9th or 8th bit depending on data width) and parity is checked on the received data.
698 * @rmtoll CR1 PS LL_USART_SetParity\n
699 * CR1 PCE LL_USART_SetParity
700 * @param USARTx USART Instance
701 * @param Parity This parameter can be one of the following values:
702 * @arg @ref LL_USART_PARITY_NONE
703 * @arg @ref LL_USART_PARITY_EVEN
704 * @arg @ref LL_USART_PARITY_ODD
705 * @retval None
707 __STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity)
709 MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity);
713 * @brief Return Parity configuration (enabled/disabled and parity mode if enabled)
714 * @rmtoll CR1 PS LL_USART_GetParity\n
715 * CR1 PCE LL_USART_GetParity
716 * @param USARTx USART Instance
717 * @retval Returned value can be one of the following values:
718 * @arg @ref LL_USART_PARITY_NONE
719 * @arg @ref LL_USART_PARITY_EVEN
720 * @arg @ref LL_USART_PARITY_ODD
722 __STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx)
724 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE));
728 * @brief Set Receiver Wake Up method from Mute mode.
729 * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod
730 * @param USARTx USART Instance
731 * @param Method This parameter can be one of the following values:
732 * @arg @ref LL_USART_WAKEUP_IDLELINE
733 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
734 * @retval None
736 __STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method)
738 MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method);
742 * @brief Return Receiver Wake Up method from Mute mode
743 * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod
744 * @param USARTx USART Instance
745 * @retval Returned value can be one of the following values:
746 * @arg @ref LL_USART_WAKEUP_IDLELINE
747 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
749 __STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx)
751 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE));
755 * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits)
756 * @rmtoll CR1 M0 LL_USART_SetDataWidth\n
757 * CR1 M1 LL_USART_SetDataWidth
758 * @param USARTx USART Instance
759 * @param DataWidth This parameter can be one of the following values:
760 * @arg @ref LL_USART_DATAWIDTH_7B (*)
761 * @arg @ref LL_USART_DATAWIDTH_8B
762 * @arg @ref LL_USART_DATAWIDTH_9B
764 * (*) Values not available on all devices
765 * @retval None
767 __STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth)
769 MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth);
773 * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits)
774 * @rmtoll CR1 M0 LL_USART_GetDataWidth\n
775 * CR1 M1 LL_USART_GetDataWidth
776 * @param USARTx USART Instance
777 * @retval Returned value can be one of the following values:
778 * @arg @ref LL_USART_DATAWIDTH_7B (*)
779 * @arg @ref LL_USART_DATAWIDTH_8B
780 * @arg @ref LL_USART_DATAWIDTH_9B
782 * (*) Values not available on all devices
784 __STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx)
786 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M));
790 * @brief Allow switch between Mute Mode and Active mode
791 * @rmtoll CR1 MME LL_USART_EnableMuteMode
792 * @param USARTx USART Instance
793 * @retval None
795 __STATIC_INLINE void LL_USART_EnableMuteMode(USART_TypeDef *USARTx)
797 SET_BIT(USARTx->CR1, USART_CR1_MME);
801 * @brief Prevent Mute Mode use. Set Receiver in active mode permanently.
802 * @rmtoll CR1 MME LL_USART_DisableMuteMode
803 * @param USARTx USART Instance
804 * @retval None
806 __STATIC_INLINE void LL_USART_DisableMuteMode(USART_TypeDef *USARTx)
808 CLEAR_BIT(USARTx->CR1, USART_CR1_MME);
812 * @brief Indicate if switch between Mute Mode and Active mode is allowed
813 * @rmtoll CR1 MME LL_USART_IsEnabledMuteMode
814 * @param USARTx USART Instance
815 * @retval State of bit (1 or 0).
817 __STATIC_INLINE uint32_t LL_USART_IsEnabledMuteMode(USART_TypeDef *USARTx)
819 return (READ_BIT(USARTx->CR1, USART_CR1_MME) == (USART_CR1_MME));
823 * @brief Set Oversampling to 8-bit or 16-bit mode
824 * @rmtoll CR1 OVER8 LL_USART_SetOverSampling
825 * @param USARTx USART Instance
826 * @param OverSampling This parameter can be one of the following values:
827 * @arg @ref LL_USART_OVERSAMPLING_16
828 * @arg @ref LL_USART_OVERSAMPLING_8
829 * @retval None
831 __STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling)
833 MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling);
837 * @brief Return Oversampling mode
838 * @rmtoll CR1 OVER8 LL_USART_GetOverSampling
839 * @param USARTx USART Instance
840 * @retval Returned value can be one of the following values:
841 * @arg @ref LL_USART_OVERSAMPLING_16
842 * @arg @ref LL_USART_OVERSAMPLING_8
844 __STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx)
846 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8));
850 * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not
851 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
852 * Synchronous mode is supported by the USARTx instance.
853 * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput
854 * @param USARTx USART Instance
855 * @param LastBitClockPulse This parameter can be one of the following values:
856 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
857 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
858 * @retval None
860 __STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse)
862 MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse);
866 * @brief Retrieve Clock pulse of the last data bit output configuration
867 * (Last bit Clock pulse output to the SCLK pin or not)
868 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
869 * Synchronous mode is supported by the USARTx instance.
870 * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput
871 * @param USARTx USART Instance
872 * @retval Returned value can be one of the following values:
873 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
874 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
876 __STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx)
878 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL));
882 * @brief Select the phase of the clock output on the SCLK pin in synchronous mode
883 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
884 * Synchronous mode is supported by the USARTx instance.
885 * @rmtoll CR2 CPHA LL_USART_SetClockPhase
886 * @param USARTx USART Instance
887 * @param ClockPhase This parameter can be one of the following values:
888 * @arg @ref LL_USART_PHASE_1EDGE
889 * @arg @ref LL_USART_PHASE_2EDGE
890 * @retval None
892 __STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase)
894 MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase);
898 * @brief Return phase of the clock output on the SCLK pin in synchronous mode
899 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
900 * Synchronous mode is supported by the USARTx instance.
901 * @rmtoll CR2 CPHA LL_USART_GetClockPhase
902 * @param USARTx USART Instance
903 * @retval Returned value can be one of the following values:
904 * @arg @ref LL_USART_PHASE_1EDGE
905 * @arg @ref LL_USART_PHASE_2EDGE
907 __STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx)
909 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA));
913 * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode
914 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
915 * Synchronous mode is supported by the USARTx instance.
916 * @rmtoll CR2 CPOL LL_USART_SetClockPolarity
917 * @param USARTx USART Instance
918 * @param ClockPolarity This parameter can be one of the following values:
919 * @arg @ref LL_USART_POLARITY_LOW
920 * @arg @ref LL_USART_POLARITY_HIGH
921 * @retval None
923 __STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity)
925 MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity);
929 * @brief Return polarity of the clock output on the SCLK pin in synchronous mode
930 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
931 * Synchronous mode is supported by the USARTx instance.
932 * @rmtoll CR2 CPOL LL_USART_GetClockPolarity
933 * @param USARTx USART Instance
934 * @retval Returned value can be one of the following values:
935 * @arg @ref LL_USART_POLARITY_LOW
936 * @arg @ref LL_USART_POLARITY_HIGH
938 __STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx)
940 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL));
944 * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse)
945 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
946 * Synchronous mode is supported by the USARTx instance.
947 * @note Call of this function is equivalent to following function call sequence :
948 * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function
949 * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function
950 * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function
951 * @rmtoll CR2 CPHA LL_USART_ConfigClock\n
952 * CR2 CPOL LL_USART_ConfigClock\n
953 * CR2 LBCL LL_USART_ConfigClock
954 * @param USARTx USART Instance
955 * @param Phase This parameter can be one of the following values:
956 * @arg @ref LL_USART_PHASE_1EDGE
957 * @arg @ref LL_USART_PHASE_2EDGE
958 * @param Polarity This parameter can be one of the following values:
959 * @arg @ref LL_USART_POLARITY_LOW
960 * @arg @ref LL_USART_POLARITY_HIGH
961 * @param LBCPOutput This parameter can be one of the following values:
962 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
963 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
964 * @retval None
966 __STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput)
968 MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput);
972 * @brief Enable Clock output on SCLK pin
973 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
974 * Synchronous mode is supported by the USARTx instance.
975 * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput
976 * @param USARTx USART Instance
977 * @retval None
979 __STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx)
981 SET_BIT(USARTx->CR2, USART_CR2_CLKEN);
985 * @brief Disable Clock output on SCLK pin
986 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
987 * Synchronous mode is supported by the USARTx instance.
988 * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput
989 * @param USARTx USART Instance
990 * @retval None
992 __STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx)
994 CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN);
998 * @brief Indicate if Clock output on SCLK pin is enabled
999 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
1000 * Synchronous mode is supported by the USARTx instance.
1001 * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput
1002 * @param USARTx USART Instance
1003 * @retval State of bit (1 or 0).
1005 __STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx)
1007 return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN));
1011 * @brief Set the length of the stop bits
1012 * @rmtoll CR2 STOP LL_USART_SetStopBitsLength
1013 * @param USARTx USART Instance
1014 * @param StopBits This parameter can be one of the following values:
1015 * @arg @ref LL_USART_STOPBITS_0_5
1016 * @arg @ref LL_USART_STOPBITS_1
1017 * @arg @ref LL_USART_STOPBITS_1_5
1018 * @arg @ref LL_USART_STOPBITS_2
1019 * @retval None
1021 __STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits)
1023 MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits);
1027 * @brief Retrieve the length of the stop bits
1028 * @rmtoll CR2 STOP LL_USART_GetStopBitsLength
1029 * @param USARTx USART Instance
1030 * @retval Returned value can be one of the following values:
1031 * @arg @ref LL_USART_STOPBITS_0_5
1032 * @arg @ref LL_USART_STOPBITS_1
1033 * @arg @ref LL_USART_STOPBITS_1_5
1034 * @arg @ref LL_USART_STOPBITS_2
1036 __STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx)
1038 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP));
1042 * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits)
1043 * @note Call of this function is equivalent to following function call sequence :
1044 * - Data Width configuration using @ref LL_USART_SetDataWidth() function
1045 * - Parity Control and mode configuration using @ref LL_USART_SetParity() function
1046 * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function
1047 * @rmtoll CR1 PS LL_USART_ConfigCharacter\n
1048 * CR1 PCE LL_USART_ConfigCharacter\n
1049 * CR1 M0 LL_USART_ConfigCharacter\n
1050 * CR1 M1 LL_USART_ConfigCharacter\n
1051 * CR2 STOP LL_USART_ConfigCharacter
1052 * @param USARTx USART Instance
1053 * @param DataWidth This parameter can be one of the following values:
1054 * @arg @ref LL_USART_DATAWIDTH_7B (*)
1055 * @arg @ref LL_USART_DATAWIDTH_8B
1056 * @arg @ref LL_USART_DATAWIDTH_9B
1057 * @param Parity This parameter can be one of the following values:
1058 * @arg @ref LL_USART_PARITY_NONE
1059 * @arg @ref LL_USART_PARITY_EVEN
1060 * @arg @ref LL_USART_PARITY_ODD
1061 * @param StopBits This parameter can be one of the following values:
1062 * @arg @ref LL_USART_STOPBITS_0_5
1063 * @arg @ref LL_USART_STOPBITS_1
1064 * @arg @ref LL_USART_STOPBITS_1_5
1065 * @arg @ref LL_USART_STOPBITS_2
1067 * (*) Values not available on all devices
1068 * @retval None
1070 __STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity,
1071 uint32_t StopBits)
1073 MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth);
1074 MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits);
1078 * @brief Configure TX/RX pins swapping setting.
1079 * @rmtoll CR2 SWAP LL_USART_SetTXRXSwap
1080 * @param USARTx USART Instance
1081 * @param SwapConfig This parameter can be one of the following values:
1082 * @arg @ref LL_USART_TXRX_STANDARD
1083 * @arg @ref LL_USART_TXRX_SWAPPED
1084 * @retval None
1086 __STATIC_INLINE void LL_USART_SetTXRXSwap(USART_TypeDef *USARTx, uint32_t SwapConfig)
1088 MODIFY_REG(USARTx->CR2, USART_CR2_SWAP, SwapConfig);
1092 * @brief Retrieve TX/RX pins swapping configuration.
1093 * @rmtoll CR2 SWAP LL_USART_GetTXRXSwap
1094 * @param USARTx USART Instance
1095 * @retval Returned value can be one of the following values:
1096 * @arg @ref LL_USART_TXRX_STANDARD
1097 * @arg @ref LL_USART_TXRX_SWAPPED
1099 __STATIC_INLINE uint32_t LL_USART_GetTXRXSwap(USART_TypeDef *USARTx)
1101 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_SWAP));
1105 * @brief Configure RX pin active level logic
1106 * @rmtoll CR2 RXINV LL_USART_SetRXPinLevel
1107 * @param USARTx USART Instance
1108 * @param PinInvMethod This parameter can be one of the following values:
1109 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1110 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1111 * @retval None
1113 __STATIC_INLINE void LL_USART_SetRXPinLevel(USART_TypeDef *USARTx, uint32_t PinInvMethod)
1115 MODIFY_REG(USARTx->CR2, USART_CR2_RXINV, PinInvMethod);
1119 * @brief Retrieve RX pin active level logic configuration
1120 * @rmtoll CR2 RXINV LL_USART_GetRXPinLevel
1121 * @param USARTx USART Instance
1122 * @retval Returned value can be one of the following values:
1123 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1124 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1126 __STATIC_INLINE uint32_t LL_USART_GetRXPinLevel(USART_TypeDef *USARTx)
1128 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_RXINV));
1132 * @brief Configure TX pin active level logic
1133 * @rmtoll CR2 TXINV LL_USART_SetTXPinLevel
1134 * @param USARTx USART Instance
1135 * @param PinInvMethod This parameter can be one of the following values:
1136 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1137 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1138 * @retval None
1140 __STATIC_INLINE void LL_USART_SetTXPinLevel(USART_TypeDef *USARTx, uint32_t PinInvMethod)
1142 MODIFY_REG(USARTx->CR2, USART_CR2_TXINV, PinInvMethod);
1146 * @brief Retrieve TX pin active level logic configuration
1147 * @rmtoll CR2 TXINV LL_USART_GetTXPinLevel
1148 * @param USARTx USART Instance
1149 * @retval Returned value can be one of the following values:
1150 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1151 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1153 __STATIC_INLINE uint32_t LL_USART_GetTXPinLevel(USART_TypeDef *USARTx)
1155 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_TXINV));
1159 * @brief Configure Binary data logic.
1160 * @note Allow to define how Logical data from the data register are send/received :
1161 * either in positive/direct logic (1=H, 0=L) or in negative/inverse logic (1=L, 0=H)
1162 * @rmtoll CR2 DATAINV LL_USART_SetBinaryDataLogic
1163 * @param USARTx USART Instance
1164 * @param DataLogic This parameter can be one of the following values:
1165 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1166 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1167 * @retval None
1169 __STATIC_INLINE void LL_USART_SetBinaryDataLogic(USART_TypeDef *USARTx, uint32_t DataLogic)
1171 MODIFY_REG(USARTx->CR2, USART_CR2_DATAINV, DataLogic);
1175 * @brief Retrieve Binary data configuration
1176 * @rmtoll CR2 DATAINV LL_USART_GetBinaryDataLogic
1177 * @param USARTx USART Instance
1178 * @retval Returned value can be one of the following values:
1179 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1180 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1182 __STATIC_INLINE uint32_t LL_USART_GetBinaryDataLogic(USART_TypeDef *USARTx)
1184 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_DATAINV));
1188 * @brief Configure transfer bit order (either Less or Most Significant Bit First)
1189 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1190 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1191 * @rmtoll CR2 MSBFIRST LL_USART_SetTransferBitOrder
1192 * @param USARTx USART Instance
1193 * @param BitOrder This parameter can be one of the following values:
1194 * @arg @ref LL_USART_BITORDER_LSBFIRST
1195 * @arg @ref LL_USART_BITORDER_MSBFIRST
1196 * @retval None
1198 __STATIC_INLINE void LL_USART_SetTransferBitOrder(USART_TypeDef *USARTx, uint32_t BitOrder)
1200 MODIFY_REG(USARTx->CR2, USART_CR2_MSBFIRST, BitOrder);
1204 * @brief Return transfer bit order (either Less or Most Significant Bit First)
1205 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1206 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1207 * @rmtoll CR2 MSBFIRST LL_USART_GetTransferBitOrder
1208 * @param USARTx USART Instance
1209 * @retval Returned value can be one of the following values:
1210 * @arg @ref LL_USART_BITORDER_LSBFIRST
1211 * @arg @ref LL_USART_BITORDER_MSBFIRST
1213 __STATIC_INLINE uint32_t LL_USART_GetTransferBitOrder(USART_TypeDef *USARTx)
1215 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_MSBFIRST));
1219 * @brief Enable Auto Baud-Rate Detection
1220 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1221 * Auto Baud Rate detection feature is supported by the USARTx instance.
1222 * @rmtoll CR2 ABREN LL_USART_EnableAutoBaudRate
1223 * @param USARTx USART Instance
1224 * @retval None
1226 __STATIC_INLINE void LL_USART_EnableAutoBaudRate(USART_TypeDef *USARTx)
1228 SET_BIT(USARTx->CR2, USART_CR2_ABREN);
1232 * @brief Disable Auto Baud-Rate Detection
1233 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1234 * Auto Baud Rate detection feature is supported by the USARTx instance.
1235 * @rmtoll CR2 ABREN LL_USART_DisableAutoBaudRate
1236 * @param USARTx USART Instance
1237 * @retval None
1239 __STATIC_INLINE void LL_USART_DisableAutoBaudRate(USART_TypeDef *USARTx)
1241 CLEAR_BIT(USARTx->CR2, USART_CR2_ABREN);
1245 * @brief Indicate if Auto Baud-Rate Detection mechanism is enabled
1246 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1247 * Auto Baud Rate detection feature is supported by the USARTx instance.
1248 * @rmtoll CR2 ABREN LL_USART_IsEnabledAutoBaud
1249 * @param USARTx USART Instance
1250 * @retval State of bit (1 or 0).
1252 __STATIC_INLINE uint32_t LL_USART_IsEnabledAutoBaud(USART_TypeDef *USARTx)
1254 return (READ_BIT(USARTx->CR2, USART_CR2_ABREN) == (USART_CR2_ABREN));
1258 * @brief Set Auto Baud-Rate mode bits
1259 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1260 * Auto Baud Rate detection feature is supported by the USARTx instance.
1261 * @rmtoll CR2 ABRMODE LL_USART_SetAutoBaudRateMode
1262 * @param USARTx USART Instance
1263 * @param AutoBaudRateMode This parameter can be one of the following values:
1264 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1265 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1266 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1267 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1268 * @retval None
1270 __STATIC_INLINE void LL_USART_SetAutoBaudRateMode(USART_TypeDef *USARTx, uint32_t AutoBaudRateMode)
1272 MODIFY_REG(USARTx->CR2, USART_CR2_ABRMODE, AutoBaudRateMode);
1276 * @brief Return Auto Baud-Rate mode
1277 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1278 * Auto Baud Rate detection feature is supported by the USARTx instance.
1279 * @rmtoll CR2 ABRMODE LL_USART_GetAutoBaudRateMode
1280 * @param USARTx USART Instance
1281 * @retval Returned value can be one of the following values:
1282 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1283 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1284 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1285 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1287 __STATIC_INLINE uint32_t LL_USART_GetAutoBaudRateMode(USART_TypeDef *USARTx)
1289 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ABRMODE));
1293 * @brief Enable Receiver Timeout
1294 * @rmtoll CR2 RTOEN LL_USART_EnableRxTimeout
1295 * @param USARTx USART Instance
1296 * @retval None
1298 __STATIC_INLINE void LL_USART_EnableRxTimeout(USART_TypeDef *USARTx)
1300 SET_BIT(USARTx->CR2, USART_CR2_RTOEN);
1304 * @brief Disable Receiver Timeout
1305 * @rmtoll CR2 RTOEN LL_USART_DisableRxTimeout
1306 * @param USARTx USART Instance
1307 * @retval None
1309 __STATIC_INLINE void LL_USART_DisableRxTimeout(USART_TypeDef *USARTx)
1311 CLEAR_BIT(USARTx->CR2, USART_CR2_RTOEN);
1315 * @brief Indicate if Receiver Timeout feature is enabled
1316 * @rmtoll CR2 RTOEN LL_USART_IsEnabledRxTimeout
1317 * @param USARTx USART Instance
1318 * @retval State of bit (1 or 0).
1320 __STATIC_INLINE uint32_t LL_USART_IsEnabledRxTimeout(USART_TypeDef *USARTx)
1322 return (READ_BIT(USARTx->CR2, USART_CR2_RTOEN) == (USART_CR2_RTOEN));
1326 * @brief Set Address of the USART node.
1327 * @note This is used in multiprocessor communication during Mute mode or Stop mode,
1328 * for wake up with address mark detection.
1329 * @note 4bits address node is used when 4-bit Address Detection is selected in ADDM7.
1330 * (b7-b4 should be set to 0)
1331 * 8bits address node is used when 7-bit Address Detection is selected in ADDM7.
1332 * (This is used in multiprocessor communication during Mute mode or Stop mode,
1333 * for wake up with 7-bit address mark detection.
1334 * The MSB of the character sent by the transmitter should be equal to 1.
1335 * It may also be used for character detection during normal reception,
1336 * Mute mode inactive (for example, end of block detection in ModBus protocol).
1337 * In this case, the whole received character (8-bit) is compared to the ADD[7:0]
1338 * value and CMF flag is set on match)
1339 * @rmtoll CR2 ADD LL_USART_ConfigNodeAddress\n
1340 * CR2 ADDM7 LL_USART_ConfigNodeAddress
1341 * @param USARTx USART Instance
1342 * @param AddressLen This parameter can be one of the following values:
1343 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1344 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1345 * @param NodeAddress 4 or 7 bit Address of the USART node.
1346 * @retval None
1348 __STATIC_INLINE void LL_USART_ConfigNodeAddress(USART_TypeDef *USARTx, uint32_t AddressLen, uint32_t NodeAddress)
1350 MODIFY_REG(USARTx->CR2, USART_CR2_ADD | USART_CR2_ADDM7,
1351 (uint32_t)(AddressLen | (NodeAddress << USART_CR2_ADD_Pos)));
1355 * @brief Return 8 bit Address of the USART node as set in ADD field of CR2.
1356 * @note If 4-bit Address Detection is selected in ADDM7,
1357 * only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant)
1358 * If 7-bit Address Detection is selected in ADDM7,
1359 * only 8bits (b7-b0) of returned value are relevant (b31-b8 are not relevant)
1360 * @rmtoll CR2 ADD LL_USART_GetNodeAddress
1361 * @param USARTx USART Instance
1362 * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255)
1364 __STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx)
1366 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD) >> USART_CR2_ADD_Pos);
1370 * @brief Return Length of Node Address used in Address Detection mode (7-bit or 4-bit)
1371 * @rmtoll CR2 ADDM7 LL_USART_GetNodeAddressLen
1372 * @param USARTx USART Instance
1373 * @retval Returned value can be one of the following values:
1374 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1375 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1377 __STATIC_INLINE uint32_t LL_USART_GetNodeAddressLen(USART_TypeDef *USARTx)
1379 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADDM7));
1383 * @brief Enable RTS HW Flow Control
1384 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1385 * Hardware Flow control feature is supported by the USARTx instance.
1386 * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl
1387 * @param USARTx USART Instance
1388 * @retval None
1390 __STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx)
1392 SET_BIT(USARTx->CR3, USART_CR3_RTSE);
1396 * @brief Disable RTS HW Flow Control
1397 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1398 * Hardware Flow control feature is supported by the USARTx instance.
1399 * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl
1400 * @param USARTx USART Instance
1401 * @retval None
1403 __STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx)
1405 CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE);
1409 * @brief Enable CTS HW Flow Control
1410 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1411 * Hardware Flow control feature is supported by the USARTx instance.
1412 * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl
1413 * @param USARTx USART Instance
1414 * @retval None
1416 __STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx)
1418 SET_BIT(USARTx->CR3, USART_CR3_CTSE);
1422 * @brief Disable CTS HW Flow Control
1423 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1424 * Hardware Flow control feature is supported by the USARTx instance.
1425 * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl
1426 * @param USARTx USART Instance
1427 * @retval None
1429 __STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx)
1431 CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE);
1435 * @brief Configure HW Flow Control mode (both CTS and RTS)
1436 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1437 * Hardware Flow control feature is supported by the USARTx instance.
1438 * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n
1439 * CR3 CTSE LL_USART_SetHWFlowCtrl
1440 * @param USARTx USART Instance
1441 * @param HardwareFlowControl This parameter can be one of the following values:
1442 * @arg @ref LL_USART_HWCONTROL_NONE
1443 * @arg @ref LL_USART_HWCONTROL_RTS
1444 * @arg @ref LL_USART_HWCONTROL_CTS
1445 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1446 * @retval None
1448 __STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl)
1450 MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl);
1454 * @brief Return HW Flow Control configuration (both CTS and RTS)
1455 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1456 * Hardware Flow control feature is supported by the USARTx instance.
1457 * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n
1458 * CR3 CTSE LL_USART_GetHWFlowCtrl
1459 * @param USARTx USART Instance
1460 * @retval Returned value can be one of the following values:
1461 * @arg @ref LL_USART_HWCONTROL_NONE
1462 * @arg @ref LL_USART_HWCONTROL_RTS
1463 * @arg @ref LL_USART_HWCONTROL_CTS
1464 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1466 __STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx)
1468 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE));
1472 * @brief Enable One bit sampling method
1473 * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp
1474 * @param USARTx USART Instance
1475 * @retval None
1477 __STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx)
1479 SET_BIT(USARTx->CR3, USART_CR3_ONEBIT);
1483 * @brief Disable One bit sampling method
1484 * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp
1485 * @param USARTx USART Instance
1486 * @retval None
1488 __STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx)
1490 CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT);
1494 * @brief Indicate if One bit sampling method is enabled
1495 * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp
1496 * @param USARTx USART Instance
1497 * @retval State of bit (1 or 0).
1499 __STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx)
1501 return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT));
1505 * @brief Enable Overrun detection
1506 * @rmtoll CR3 OVRDIS LL_USART_EnableOverrunDetect
1507 * @param USARTx USART Instance
1508 * @retval None
1510 __STATIC_INLINE void LL_USART_EnableOverrunDetect(USART_TypeDef *USARTx)
1512 CLEAR_BIT(USARTx->CR3, USART_CR3_OVRDIS);
1516 * @brief Disable Overrun detection
1517 * @rmtoll CR3 OVRDIS LL_USART_DisableOverrunDetect
1518 * @param USARTx USART Instance
1519 * @retval None
1521 __STATIC_INLINE void LL_USART_DisableOverrunDetect(USART_TypeDef *USARTx)
1523 SET_BIT(USARTx->CR3, USART_CR3_OVRDIS);
1527 * @brief Indicate if Overrun detection is enabled
1528 * @rmtoll CR3 OVRDIS LL_USART_IsEnabledOverrunDetect
1529 * @param USARTx USART Instance
1530 * @retval State of bit (1 or 0).
1532 __STATIC_INLINE uint32_t LL_USART_IsEnabledOverrunDetect(USART_TypeDef *USARTx)
1534 return (READ_BIT(USARTx->CR3, USART_CR3_OVRDIS) != USART_CR3_OVRDIS);
1538 * @brief Select event type for Wake UP Interrupt Flag (WUS[1:0] bits)
1539 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
1540 * Wake-up from Stop mode feature is supported by the USARTx instance.
1541 * @rmtoll CR3 WUS LL_USART_SetWKUPType
1542 * @param USARTx USART Instance
1543 * @param Type This parameter can be one of the following values:
1544 * @arg @ref LL_USART_WAKEUP_ON_ADDRESS
1545 * @arg @ref LL_USART_WAKEUP_ON_STARTBIT
1546 * @arg @ref LL_USART_WAKEUP_ON_RXNE
1547 * @retval None
1549 __STATIC_INLINE void LL_USART_SetWKUPType(USART_TypeDef *USARTx, uint32_t Type)
1551 MODIFY_REG(USARTx->CR3, USART_CR3_WUS, Type);
1555 * @brief Return event type for Wake UP Interrupt Flag (WUS[1:0] bits)
1556 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
1557 * Wake-up from Stop mode feature is supported by the USARTx instance.
1558 * @rmtoll CR3 WUS LL_USART_GetWKUPType
1559 * @param USARTx USART Instance
1560 * @retval Returned value can be one of the following values:
1561 * @arg @ref LL_USART_WAKEUP_ON_ADDRESS
1562 * @arg @ref LL_USART_WAKEUP_ON_STARTBIT
1563 * @arg @ref LL_USART_WAKEUP_ON_RXNE
1565 __STATIC_INLINE uint32_t LL_USART_GetWKUPType(USART_TypeDef *USARTx)
1567 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_WUS));
1571 * @brief Configure USART BRR register for achieving expected Baud Rate value.
1572 * @note Compute and set USARTDIV value in BRR Register (full BRR content)
1573 * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values
1574 * @note Peripheral clock and Baud rate values provided as function parameters should be valid
1575 * (Baud rate value != 0)
1576 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1577 * @rmtoll BRR BRR LL_USART_SetBaudRate
1578 * @param USARTx USART Instance
1579 * @param PeriphClk Peripheral Clock
1580 * @param OverSampling This parameter can be one of the following values:
1581 * @arg @ref LL_USART_OVERSAMPLING_16
1582 * @arg @ref LL_USART_OVERSAMPLING_8
1583 * @param BaudRate Baud Rate
1584 * @retval None
1586 __STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling,
1587 uint32_t BaudRate)
1589 register uint32_t usartdiv = 0x0U;
1590 register uint32_t brrtemp = 0x0U;
1592 if (OverSampling == LL_USART_OVERSAMPLING_8)
1594 usartdiv = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate));
1595 brrtemp = usartdiv & 0xFFF0U;
1596 brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U);
1597 USARTx->BRR = brrtemp;
1599 else
1601 USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate));
1606 * @brief Return current Baud Rate value, according to USARTDIV present in BRR register
1607 * (full BRR content), and to used Peripheral Clock and Oversampling mode values
1608 * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned.
1609 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1610 * @rmtoll BRR BRR LL_USART_GetBaudRate
1611 * @param USARTx USART Instance
1612 * @param PeriphClk Peripheral Clock
1613 * @param OverSampling This parameter can be one of the following values:
1614 * @arg @ref LL_USART_OVERSAMPLING_16
1615 * @arg @ref LL_USART_OVERSAMPLING_8
1616 * @retval Baud Rate
1618 __STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling)
1620 register uint32_t usartdiv = 0x0U;
1621 register uint32_t brrresult = 0x0U;
1623 usartdiv = USARTx->BRR;
1625 if (OverSampling == LL_USART_OVERSAMPLING_8)
1627 if ((usartdiv & 0xFFF7U) != 0U)
1629 usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ;
1630 brrresult = (PeriphClk * 2U) / usartdiv;
1633 else
1635 if ((usartdiv & 0xFFFFU) != 0U)
1637 brrresult = PeriphClk / usartdiv;
1640 return (brrresult);
1644 * @brief Set Receiver Time Out Value (expressed in nb of bits duration)
1645 * @rmtoll RTOR RTO LL_USART_SetRxTimeout
1646 * @param USARTx USART Instance
1647 * @param Timeout Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1648 * @retval None
1650 __STATIC_INLINE void LL_USART_SetRxTimeout(USART_TypeDef *USARTx, uint32_t Timeout)
1652 MODIFY_REG(USARTx->RTOR, USART_RTOR_RTO, Timeout);
1656 * @brief Get Receiver Time Out Value (expressed in nb of bits duration)
1657 * @rmtoll RTOR RTO LL_USART_GetRxTimeout
1658 * @param USARTx USART Instance
1659 * @retval Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1661 __STATIC_INLINE uint32_t LL_USART_GetRxTimeout(USART_TypeDef *USARTx)
1663 return (uint32_t)(READ_BIT(USARTx->RTOR, USART_RTOR_RTO));
1667 * @brief Set Block Length value in reception
1668 * @rmtoll RTOR BLEN LL_USART_SetBlockLength
1669 * @param USARTx USART Instance
1670 * @param BlockLength Value between Min_Data=0x00 and Max_Data=0xFF
1671 * @retval None
1673 __STATIC_INLINE void LL_USART_SetBlockLength(USART_TypeDef *USARTx, uint32_t BlockLength)
1675 MODIFY_REG(USARTx->RTOR, USART_RTOR_BLEN, BlockLength << USART_RTOR_BLEN_Pos);
1679 * @brief Get Block Length value in reception
1680 * @rmtoll RTOR BLEN LL_USART_GetBlockLength
1681 * @param USARTx USART Instance
1682 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1684 __STATIC_INLINE uint32_t LL_USART_GetBlockLength(USART_TypeDef *USARTx)
1686 return (uint32_t)(READ_BIT(USARTx->RTOR, USART_RTOR_BLEN) >> USART_RTOR_BLEN_Pos);
1690 * @}
1693 /** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature
1694 * @{
1698 * @brief Enable IrDA mode
1699 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1700 * IrDA feature is supported by the USARTx instance.
1701 * @rmtoll CR3 IREN LL_USART_EnableIrda
1702 * @param USARTx USART Instance
1703 * @retval None
1705 __STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx)
1707 SET_BIT(USARTx->CR3, USART_CR3_IREN);
1711 * @brief Disable IrDA mode
1712 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1713 * IrDA feature is supported by the USARTx instance.
1714 * @rmtoll CR3 IREN LL_USART_DisableIrda
1715 * @param USARTx USART Instance
1716 * @retval None
1718 __STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx)
1720 CLEAR_BIT(USARTx->CR3, USART_CR3_IREN);
1724 * @brief Indicate if IrDA mode is enabled
1725 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1726 * IrDA feature is supported by the USARTx instance.
1727 * @rmtoll CR3 IREN LL_USART_IsEnabledIrda
1728 * @param USARTx USART Instance
1729 * @retval State of bit (1 or 0).
1731 __STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx)
1733 return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN));
1737 * @brief Configure IrDA Power Mode (Normal or Low Power)
1738 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1739 * IrDA feature is supported by the USARTx instance.
1740 * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode
1741 * @param USARTx USART Instance
1742 * @param PowerMode This parameter can be one of the following values:
1743 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1744 * @arg @ref LL_USART_IRDA_POWER_LOW
1745 * @retval None
1747 __STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode)
1749 MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode);
1753 * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power)
1754 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1755 * IrDA feature is supported by the USARTx instance.
1756 * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode
1757 * @param USARTx USART Instance
1758 * @retval Returned value can be one of the following values:
1759 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1760 * @arg @ref LL_USART_PHASE_2EDGE
1762 __STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx)
1764 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP));
1768 * @brief Set Irda prescaler value, used for dividing the USART clock source
1769 * to achieve the Irda Low Power frequency (8 bits value)
1770 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1771 * IrDA feature is supported by the USARTx instance.
1772 * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler
1773 * @param USARTx USART Instance
1774 * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF
1775 * @retval None
1777 __STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue)
1779 MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue);
1783 * @brief Return Irda prescaler value, used for dividing the USART clock source
1784 * to achieve the Irda Low Power frequency (8 bits value)
1785 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1786 * IrDA feature is supported by the USARTx instance.
1787 * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler
1788 * @param USARTx USART Instance
1789 * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF)
1791 __STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx)
1793 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC));
1797 * @}
1800 /** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature
1801 * @{
1805 * @brief Enable Smartcard NACK transmission
1806 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1807 * Smartcard feature is supported by the USARTx instance.
1808 * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK
1809 * @param USARTx USART Instance
1810 * @retval None
1812 __STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx)
1814 SET_BIT(USARTx->CR3, USART_CR3_NACK);
1818 * @brief Disable Smartcard NACK transmission
1819 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1820 * Smartcard feature is supported by the USARTx instance.
1821 * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK
1822 * @param USARTx USART Instance
1823 * @retval None
1825 __STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx)
1827 CLEAR_BIT(USARTx->CR3, USART_CR3_NACK);
1831 * @brief Indicate if Smartcard NACK transmission is enabled
1832 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1833 * Smartcard feature is supported by the USARTx instance.
1834 * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK
1835 * @param USARTx USART Instance
1836 * @retval State of bit (1 or 0).
1838 __STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx)
1840 return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK));
1844 * @brief Enable Smartcard mode
1845 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1846 * Smartcard feature is supported by the USARTx instance.
1847 * @rmtoll CR3 SCEN LL_USART_EnableSmartcard
1848 * @param USARTx USART Instance
1849 * @retval None
1851 __STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx)
1853 SET_BIT(USARTx->CR3, USART_CR3_SCEN);
1857 * @brief Disable Smartcard mode
1858 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1859 * Smartcard feature is supported by the USARTx instance.
1860 * @rmtoll CR3 SCEN LL_USART_DisableSmartcard
1861 * @param USARTx USART Instance
1862 * @retval None
1864 __STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx)
1866 CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN);
1870 * @brief Indicate if Smartcard mode is enabled
1871 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1872 * Smartcard feature is supported by the USARTx instance.
1873 * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard
1874 * @param USARTx USART Instance
1875 * @retval State of bit (1 or 0).
1877 __STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx)
1879 return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN));
1883 * @brief Set Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1884 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1885 * Smartcard feature is supported by the USARTx instance.
1886 * @note This bit-field specifies the number of retries in transmit and receive, in Smartcard mode.
1887 * In transmission mode, it specifies the number of automatic retransmission retries, before
1888 * generating a transmission error (FE bit set).
1889 * In reception mode, it specifies the number or erroneous reception trials, before generating a
1890 * reception error (RXNE and PE bits set)
1891 * @rmtoll CR3 SCARCNT LL_USART_SetSmartcardAutoRetryCount
1892 * @param USARTx USART Instance
1893 * @param AutoRetryCount Value between Min_Data=0 and Max_Data=7
1894 * @retval None
1896 __STATIC_INLINE void LL_USART_SetSmartcardAutoRetryCount(USART_TypeDef *USARTx, uint32_t AutoRetryCount)
1898 MODIFY_REG(USARTx->CR3, USART_CR3_SCARCNT, AutoRetryCount << USART_CR3_SCARCNT_Pos);
1902 * @brief Return Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1903 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1904 * Smartcard feature is supported by the USARTx instance.
1905 * @rmtoll CR3 SCARCNT LL_USART_GetSmartcardAutoRetryCount
1906 * @param USARTx USART Instance
1907 * @retval Smartcard Auto-Retry Count value (Value between Min_Data=0 and Max_Data=7)
1909 __STATIC_INLINE uint32_t LL_USART_GetSmartcardAutoRetryCount(USART_TypeDef *USARTx)
1911 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_SCARCNT) >> USART_CR3_SCARCNT_Pos);
1915 * @brief Set Smartcard prescaler value, used for dividing the USART clock
1916 * source to provide the SMARTCARD Clock (5 bits value)
1917 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1918 * Smartcard feature is supported by the USARTx instance.
1919 * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler
1920 * @param USARTx USART Instance
1921 * @param PrescalerValue Value between Min_Data=0 and Max_Data=31
1922 * @retval None
1924 __STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue)
1926 MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue);
1930 * @brief Return Smartcard prescaler value, used for dividing the USART clock
1931 * source to provide the SMARTCARD Clock (5 bits value)
1932 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1933 * Smartcard feature is supported by the USARTx instance.
1934 * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler
1935 * @param USARTx USART Instance
1936 * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31)
1938 __STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx)
1940 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC));
1944 * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods
1945 * (GT[7:0] bits : Guard time value)
1946 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1947 * Smartcard feature is supported by the USARTx instance.
1948 * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime
1949 * @param USARTx USART Instance
1950 * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF
1951 * @retval None
1953 __STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime)
1955 MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_GTPR_GT_Pos);
1959 * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods
1960 * (GT[7:0] bits : Guard time value)
1961 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1962 * Smartcard feature is supported by the USARTx instance.
1963 * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime
1964 * @param USARTx USART Instance
1965 * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF)
1967 __STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx)
1969 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_GTPR_GT_Pos);
1973 * @}
1976 /** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature
1977 * @{
1981 * @brief Enable Single Wire Half-Duplex mode
1982 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1983 * Half-Duplex mode is supported by the USARTx instance.
1984 * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex
1985 * @param USARTx USART Instance
1986 * @retval None
1988 __STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx)
1990 SET_BIT(USARTx->CR3, USART_CR3_HDSEL);
1994 * @brief Disable Single Wire Half-Duplex mode
1995 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1996 * Half-Duplex mode is supported by the USARTx instance.
1997 * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex
1998 * @param USARTx USART Instance
1999 * @retval None
2001 __STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx)
2003 CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL);
2007 * @brief Indicate if Single Wire Half-Duplex mode is enabled
2008 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2009 * Half-Duplex mode is supported by the USARTx instance.
2010 * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex
2011 * @param USARTx USART Instance
2012 * @retval State of bit (1 or 0).
2014 __STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx)
2016 return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL));
2020 * @}
2023 /** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature
2024 * @{
2028 * @brief Set LIN Break Detection Length
2029 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2030 * LIN feature is supported by the USARTx instance.
2031 * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen
2032 * @param USARTx USART Instance
2033 * @param LINBDLength This parameter can be one of the following values:
2034 * @arg @ref LL_USART_LINBREAK_DETECT_10B
2035 * @arg @ref LL_USART_LINBREAK_DETECT_11B
2036 * @retval None
2038 __STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength)
2040 MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength);
2044 * @brief Return LIN Break Detection Length
2045 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2046 * LIN feature is supported by the USARTx instance.
2047 * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen
2048 * @param USARTx USART Instance
2049 * @retval Returned value can be one of the following values:
2050 * @arg @ref LL_USART_LINBREAK_DETECT_10B
2051 * @arg @ref LL_USART_LINBREAK_DETECT_11B
2053 __STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx)
2055 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL));
2059 * @brief Enable LIN mode
2060 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2061 * LIN feature is supported by the USARTx instance.
2062 * @rmtoll CR2 LINEN LL_USART_EnableLIN
2063 * @param USARTx USART Instance
2064 * @retval None
2066 __STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx)
2068 SET_BIT(USARTx->CR2, USART_CR2_LINEN);
2072 * @brief Disable LIN mode
2073 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2074 * LIN feature is supported by the USARTx instance.
2075 * @rmtoll CR2 LINEN LL_USART_DisableLIN
2076 * @param USARTx USART Instance
2077 * @retval None
2079 __STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx)
2081 CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN);
2085 * @brief Indicate if LIN mode is enabled
2086 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2087 * LIN feature is supported by the USARTx instance.
2088 * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN
2089 * @param USARTx USART Instance
2090 * @retval State of bit (1 or 0).
2092 __STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx)
2094 return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN));
2098 * @}
2101 /** @defgroup USART_LL_EF_Configuration_DE Configuration functions related to Driver Enable feature
2102 * @{
2106 * @brief Set DEDT (Driver Enable De-Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2107 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2108 * Driver Enable feature is supported by the USARTx instance.
2109 * @rmtoll CR1 DEDT LL_USART_SetDEDeassertionTime
2110 * @param USARTx USART Instance
2111 * @param Time Value between Min_Data=0 and Max_Data=31
2112 * @retval None
2114 __STATIC_INLINE void LL_USART_SetDEDeassertionTime(USART_TypeDef *USARTx, uint32_t Time)
2116 MODIFY_REG(USARTx->CR1, USART_CR1_DEDT, Time << USART_CR1_DEDT_Pos);
2120 * @brief Return DEDT (Driver Enable De-Assertion Time)
2121 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2122 * Driver Enable feature is supported by the USARTx instance.
2123 * @rmtoll CR1 DEDT LL_USART_GetDEDeassertionTime
2124 * @param USARTx USART Instance
2125 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2127 __STATIC_INLINE uint32_t LL_USART_GetDEDeassertionTime(USART_TypeDef *USARTx)
2129 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_DEDT) >> USART_CR1_DEDT_Pos);
2133 * @brief Set DEAT (Driver Enable Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2134 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2135 * Driver Enable feature is supported by the USARTx instance.
2136 * @rmtoll CR1 DEAT LL_USART_SetDEAssertionTime
2137 * @param USARTx USART Instance
2138 * @param Time Value between Min_Data=0 and Max_Data=31
2139 * @retval None
2141 __STATIC_INLINE void LL_USART_SetDEAssertionTime(USART_TypeDef *USARTx, uint32_t Time)
2143 MODIFY_REG(USARTx->CR1, USART_CR1_DEAT, Time << USART_CR1_DEAT_Pos);
2147 * @brief Return DEAT (Driver Enable Assertion Time)
2148 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2149 * Driver Enable feature is supported by the USARTx instance.
2150 * @rmtoll CR1 DEAT LL_USART_GetDEAssertionTime
2151 * @param USARTx USART Instance
2152 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2154 __STATIC_INLINE uint32_t LL_USART_GetDEAssertionTime(USART_TypeDef *USARTx)
2156 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_DEAT) >> USART_CR1_DEAT_Pos);
2160 * @brief Enable Driver Enable (DE) Mode
2161 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2162 * Driver Enable feature is supported by the USARTx instance.
2163 * @rmtoll CR3 DEM LL_USART_EnableDEMode
2164 * @param USARTx USART Instance
2165 * @retval None
2167 __STATIC_INLINE void LL_USART_EnableDEMode(USART_TypeDef *USARTx)
2169 SET_BIT(USARTx->CR3, USART_CR3_DEM);
2173 * @brief Disable Driver Enable (DE) Mode
2174 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2175 * Driver Enable feature is supported by the USARTx instance.
2176 * @rmtoll CR3 DEM LL_USART_DisableDEMode
2177 * @param USARTx USART Instance
2178 * @retval None
2180 __STATIC_INLINE void LL_USART_DisableDEMode(USART_TypeDef *USARTx)
2182 CLEAR_BIT(USARTx->CR3, USART_CR3_DEM);
2186 * @brief Indicate if Driver Enable (DE) Mode is enabled
2187 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2188 * Driver Enable feature is supported by the USARTx instance.
2189 * @rmtoll CR3 DEM LL_USART_IsEnabledDEMode
2190 * @param USARTx USART Instance
2191 * @retval State of bit (1 or 0).
2193 __STATIC_INLINE uint32_t LL_USART_IsEnabledDEMode(USART_TypeDef *USARTx)
2195 return (READ_BIT(USARTx->CR3, USART_CR3_DEM) == (USART_CR3_DEM));
2199 * @brief Select Driver Enable Polarity
2200 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2201 * Driver Enable feature is supported by the USARTx instance.
2202 * @rmtoll CR3 DEP LL_USART_SetDESignalPolarity
2203 * @param USARTx USART Instance
2204 * @param Polarity This parameter can be one of the following values:
2205 * @arg @ref LL_USART_DE_POLARITY_HIGH
2206 * @arg @ref LL_USART_DE_POLARITY_LOW
2207 * @retval None
2209 __STATIC_INLINE void LL_USART_SetDESignalPolarity(USART_TypeDef *USARTx, uint32_t Polarity)
2211 MODIFY_REG(USARTx->CR3, USART_CR3_DEP, Polarity);
2215 * @brief Return Driver Enable Polarity
2216 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2217 * Driver Enable feature is supported by the USARTx instance.
2218 * @rmtoll CR3 DEP LL_USART_GetDESignalPolarity
2219 * @param USARTx USART Instance
2220 * @retval Returned value can be one of the following values:
2221 * @arg @ref LL_USART_DE_POLARITY_HIGH
2222 * @arg @ref LL_USART_DE_POLARITY_LOW
2224 __STATIC_INLINE uint32_t LL_USART_GetDESignalPolarity(USART_TypeDef *USARTx)
2226 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_DEP));
2230 * @}
2233 /** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services
2234 * @{
2238 * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART)
2239 * @note In UART mode, the following bits must be kept cleared:
2240 * - LINEN bit in the USART_CR2 register,
2241 * - CLKEN bit in the USART_CR2 register,
2242 * - SCEN bit in the USART_CR3 register,
2243 * - IREN bit in the USART_CR3 register,
2244 * - HDSEL bit in the USART_CR3 register.
2245 * @note Call of this function is equivalent to following function call sequence :
2246 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2247 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2248 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2249 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2250 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2251 * @note Other remaining configurations items related to Asynchronous Mode
2252 * (as Baud Rate, Word length, Parity, ...) should be set using
2253 * dedicated functions
2254 * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n
2255 * CR2 CLKEN LL_USART_ConfigAsyncMode\n
2256 * CR3 SCEN LL_USART_ConfigAsyncMode\n
2257 * CR3 IREN LL_USART_ConfigAsyncMode\n
2258 * CR3 HDSEL LL_USART_ConfigAsyncMode
2259 * @param USARTx USART Instance
2260 * @retval None
2262 __STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx)
2264 /* In Asynchronous mode, the following bits must be kept cleared:
2265 - LINEN, CLKEN bits in the USART_CR2 register,
2266 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2267 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2268 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL));
2272 * @brief Perform basic configuration of USART for enabling use in Synchronous Mode
2273 * @note In Synchronous mode, the following bits must be kept cleared:
2274 * - LINEN bit in the USART_CR2 register,
2275 * - SCEN bit in the USART_CR3 register,
2276 * - IREN bit in the USART_CR3 register,
2277 * - HDSEL bit in the USART_CR3 register.
2278 * This function also sets the USART in Synchronous mode.
2279 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
2280 * Synchronous mode is supported by the USARTx instance.
2281 * @note Call of this function is equivalent to following function call sequence :
2282 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2283 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2284 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2285 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2286 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2287 * @note Other remaining configurations items related to Synchronous Mode
2288 * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using
2289 * dedicated functions
2290 * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n
2291 * CR2 CLKEN LL_USART_ConfigSyncMode\n
2292 * CR3 SCEN LL_USART_ConfigSyncMode\n
2293 * CR3 IREN LL_USART_ConfigSyncMode\n
2294 * CR3 HDSEL LL_USART_ConfigSyncMode
2295 * @param USARTx USART Instance
2296 * @retval None
2298 __STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx)
2300 /* In Synchronous mode, the following bits must be kept cleared:
2301 - LINEN bit in the USART_CR2 register,
2302 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2303 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN));
2304 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL));
2305 /* set the UART/USART in Synchronous mode */
2306 SET_BIT(USARTx->CR2, USART_CR2_CLKEN);
2310 * @brief Perform basic configuration of USART for enabling use in LIN Mode
2311 * @note In LIN mode, the following bits must be kept cleared:
2312 * - STOP and CLKEN bits in the USART_CR2 register,
2313 * - SCEN bit in the USART_CR3 register,
2314 * - IREN bit in the USART_CR3 register,
2315 * - HDSEL bit in the USART_CR3 register.
2316 * This function also set the UART/USART in LIN mode.
2317 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2318 * LIN feature is supported by the USARTx instance.
2319 * @note Call of this function is equivalent to following function call sequence :
2320 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2321 * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2322 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2323 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2324 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2325 * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function
2326 * @note Other remaining configurations items related to LIN Mode
2327 * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using
2328 * dedicated functions
2329 * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n
2330 * CR2 STOP LL_USART_ConfigLINMode\n
2331 * CR2 LINEN LL_USART_ConfigLINMode\n
2332 * CR3 IREN LL_USART_ConfigLINMode\n
2333 * CR3 SCEN LL_USART_ConfigLINMode\n
2334 * CR3 HDSEL LL_USART_ConfigLINMode
2335 * @param USARTx USART Instance
2336 * @retval None
2338 __STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx)
2340 /* In LIN mode, the following bits must be kept cleared:
2341 - STOP and CLKEN bits in the USART_CR2 register,
2342 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2343 CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP));
2344 CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL));
2345 /* Set the UART/USART in LIN mode */
2346 SET_BIT(USARTx->CR2, USART_CR2_LINEN);
2350 * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode
2351 * @note In Half Duplex mode, the following bits must be kept cleared:
2352 * - LINEN bit in the USART_CR2 register,
2353 * - CLKEN bit in the USART_CR2 register,
2354 * - SCEN bit in the USART_CR3 register,
2355 * - IREN bit in the USART_CR3 register,
2356 * This function also sets the UART/USART in Half Duplex mode.
2357 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2358 * Half-Duplex mode is supported by the USARTx instance.
2359 * @note Call of this function is equivalent to following function call sequence :
2360 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2361 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2362 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2363 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2364 * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function
2365 * @note Other remaining configurations items related to Half Duplex Mode
2366 * (as Baud Rate, Word length, Parity, ...) should be set using
2367 * dedicated functions
2368 * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n
2369 * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n
2370 * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n
2371 * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n
2372 * CR3 IREN LL_USART_ConfigHalfDuplexMode
2373 * @param USARTx USART Instance
2374 * @retval None
2376 __STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx)
2378 /* In Half Duplex mode, the following bits must be kept cleared:
2379 - LINEN and CLKEN bits in the USART_CR2 register,
2380 - SCEN and IREN bits in the USART_CR3 register.*/
2381 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2382 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN));
2383 /* set the UART/USART in Half Duplex mode */
2384 SET_BIT(USARTx->CR3, USART_CR3_HDSEL);
2388 * @brief Perform basic configuration of USART for enabling use in Smartcard Mode
2389 * @note In Smartcard mode, the following bits must be kept cleared:
2390 * - LINEN bit in the USART_CR2 register,
2391 * - IREN bit in the USART_CR3 register,
2392 * - HDSEL bit in the USART_CR3 register.
2393 * This function also configures Stop bits to 1.5 bits and
2394 * sets the USART in Smartcard mode (SCEN bit).
2395 * Clock Output is also enabled (CLKEN).
2396 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2397 * Smartcard feature is supported by the USARTx instance.
2398 * @note Call of this function is equivalent to following function call sequence :
2399 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2400 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2401 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2402 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2403 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2404 * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function
2405 * @note Other remaining configurations items related to Smartcard Mode
2406 * (as Baud Rate, Word length, Parity, ...) should be set using
2407 * dedicated functions
2408 * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n
2409 * CR2 STOP LL_USART_ConfigSmartcardMode\n
2410 * CR2 CLKEN LL_USART_ConfigSmartcardMode\n
2411 * CR3 HDSEL LL_USART_ConfigSmartcardMode\n
2412 * CR3 SCEN LL_USART_ConfigSmartcardMode
2413 * @param USARTx USART Instance
2414 * @retval None
2416 __STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx)
2418 /* In Smartcard mode, the following bits must be kept cleared:
2419 - LINEN bit in the USART_CR2 register,
2420 - IREN and HDSEL bits in the USART_CR3 register.*/
2421 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN));
2422 CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL));
2423 /* Configure Stop bits to 1.5 bits */
2424 /* Synchronous mode is activated by default */
2425 SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN));
2426 /* set the UART/USART in Smartcard mode */
2427 SET_BIT(USARTx->CR3, USART_CR3_SCEN);
2431 * @brief Perform basic configuration of USART for enabling use in Irda Mode
2432 * @note In IRDA mode, the following bits must be kept cleared:
2433 * - LINEN bit in the USART_CR2 register,
2434 * - STOP and CLKEN bits in the USART_CR2 register,
2435 * - SCEN bit in the USART_CR3 register,
2436 * - HDSEL bit in the USART_CR3 register.
2437 * This function also sets the UART/USART in IRDA mode (IREN bit).
2438 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2439 * IrDA feature is supported by the USARTx instance.
2440 * @note Call of this function is equivalent to following function call sequence :
2441 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2442 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2443 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2444 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2445 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2446 * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function
2447 * @note Other remaining configurations items related to Irda Mode
2448 * (as Baud Rate, Word length, Power mode, ...) should be set using
2449 * dedicated functions
2450 * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n
2451 * CR2 CLKEN LL_USART_ConfigIrdaMode\n
2452 * CR2 STOP LL_USART_ConfigIrdaMode\n
2453 * CR3 SCEN LL_USART_ConfigIrdaMode\n
2454 * CR3 HDSEL LL_USART_ConfigIrdaMode\n
2455 * CR3 IREN LL_USART_ConfigIrdaMode
2456 * @param USARTx USART Instance
2457 * @retval None
2459 __STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx)
2461 /* In IRDA mode, the following bits must be kept cleared:
2462 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
2463 - SCEN and HDSEL bits in the USART_CR3 register.*/
2464 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP));
2465 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL));
2466 /* set the UART/USART in IRDA mode */
2467 SET_BIT(USARTx->CR3, USART_CR3_IREN);
2471 * @brief Perform basic configuration of USART for enabling use in Multi processor Mode
2472 * (several USARTs connected in a network, one of the USARTs can be the master,
2473 * its TX output connected to the RX inputs of the other slaves USARTs).
2474 * @note In MultiProcessor mode, the following bits must be kept cleared:
2475 * - LINEN bit in the USART_CR2 register,
2476 * - CLKEN bit in the USART_CR2 register,
2477 * - SCEN bit in the USART_CR3 register,
2478 * - IREN bit in the USART_CR3 register,
2479 * - HDSEL bit in the USART_CR3 register.
2480 * @note Call of this function is equivalent to following function call sequence :
2481 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2482 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2483 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2484 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2485 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2486 * @note Other remaining configurations items related to Multi processor Mode
2487 * (as Baud Rate, Wake Up Method, Node address, ...) should be set using
2488 * dedicated functions
2489 * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n
2490 * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n
2491 * CR3 SCEN LL_USART_ConfigMultiProcessMode\n
2492 * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n
2493 * CR3 IREN LL_USART_ConfigMultiProcessMode
2494 * @param USARTx USART Instance
2495 * @retval None
2497 __STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx)
2499 /* In Multi Processor mode, the following bits must be kept cleared:
2500 - LINEN and CLKEN bits in the USART_CR2 register,
2501 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2502 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2503 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN));
2507 * @}
2510 /** @defgroup USART_LL_EF_FLAG_Management FLAG_Management
2511 * @{
2515 * @brief Check if the USART Parity Error Flag is set or not
2516 * @rmtoll ISR PE LL_USART_IsActiveFlag_PE
2517 * @param USARTx USART Instance
2518 * @retval State of bit (1 or 0).
2520 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx)
2522 return (READ_BIT(USARTx->ISR, USART_ISR_PE) == (USART_ISR_PE));
2526 * @brief Check if the USART Framing Error Flag is set or not
2527 * @rmtoll ISR FE LL_USART_IsActiveFlag_FE
2528 * @param USARTx USART Instance
2529 * @retval State of bit (1 or 0).
2531 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx)
2533 return (READ_BIT(USARTx->ISR, USART_ISR_FE) == (USART_ISR_FE));
2537 * @brief Check if the USART Noise error detected Flag is set or not
2538 * @rmtoll ISR NF LL_USART_IsActiveFlag_NE
2539 * @param USARTx USART Instance
2540 * @retval State of bit (1 or 0).
2542 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx)
2544 return (READ_BIT(USARTx->ISR, USART_ISR_NE) == (USART_ISR_NE));
2548 * @brief Check if the USART OverRun Error Flag is set or not
2549 * @rmtoll ISR ORE LL_USART_IsActiveFlag_ORE
2550 * @param USARTx USART Instance
2551 * @retval State of bit (1 or 0).
2553 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx)
2555 return (READ_BIT(USARTx->ISR, USART_ISR_ORE) == (USART_ISR_ORE));
2559 * @brief Check if the USART IDLE line detected Flag is set or not
2560 * @rmtoll ISR IDLE LL_USART_IsActiveFlag_IDLE
2561 * @param USARTx USART Instance
2562 * @retval State of bit (1 or 0).
2564 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx)
2566 return (READ_BIT(USARTx->ISR, USART_ISR_IDLE) == (USART_ISR_IDLE));
2570 * @brief Check if the USART Read Data Register Not Empty Flag is set or not
2571 * @rmtoll ISR RXNE LL_USART_IsActiveFlag_RXNE
2572 * @param USARTx USART Instance
2573 * @retval State of bit (1 or 0).
2575 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx)
2577 return (READ_BIT(USARTx->ISR, USART_ISR_RXNE) == (USART_ISR_RXNE));
2581 * @brief Check if the USART Transmission Complete Flag is set or not
2582 * @rmtoll ISR TC LL_USART_IsActiveFlag_TC
2583 * @param USARTx USART Instance
2584 * @retval State of bit (1 or 0).
2586 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx)
2588 return (READ_BIT(USARTx->ISR, USART_ISR_TC) == (USART_ISR_TC));
2592 * @brief Check if the USART Transmit Data Register Empty Flag is set or not
2593 * @rmtoll ISR TXE LL_USART_IsActiveFlag_TXE
2594 * @param USARTx USART Instance
2595 * @retval State of bit (1 or 0).
2597 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx)
2599 return (READ_BIT(USARTx->ISR, USART_ISR_TXE) == (USART_ISR_TXE));
2603 * @brief Check if the USART LIN Break Detection Flag is set or not
2604 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2605 * LIN feature is supported by the USARTx instance.
2606 * @rmtoll ISR LBDF LL_USART_IsActiveFlag_LBD
2607 * @param USARTx USART Instance
2608 * @retval State of bit (1 or 0).
2610 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx)
2612 return (READ_BIT(USARTx->ISR, USART_ISR_LBDF) == (USART_ISR_LBDF));
2616 * @brief Check if the USART CTS interrupt Flag is set or not
2617 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2618 * Hardware Flow control feature is supported by the USARTx instance.
2619 * @rmtoll ISR CTSIF LL_USART_IsActiveFlag_nCTS
2620 * @param USARTx USART Instance
2621 * @retval State of bit (1 or 0).
2623 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx)
2625 return (READ_BIT(USARTx->ISR, USART_ISR_CTSIF) == (USART_ISR_CTSIF));
2629 * @brief Check if the USART CTS Flag is set or not
2630 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2631 * Hardware Flow control feature is supported by the USARTx instance.
2632 * @rmtoll ISR CTS LL_USART_IsActiveFlag_CTS
2633 * @param USARTx USART Instance
2634 * @retval State of bit (1 or 0).
2636 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_CTS(USART_TypeDef *USARTx)
2638 return (READ_BIT(USARTx->ISR, USART_ISR_CTS) == (USART_ISR_CTS));
2642 * @brief Check if the USART Receiver Time Out Flag is set or not
2643 * @rmtoll ISR RTOF LL_USART_IsActiveFlag_RTO
2644 * @param USARTx USART Instance
2645 * @retval State of bit (1 or 0).
2647 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RTO(USART_TypeDef *USARTx)
2649 return (READ_BIT(USARTx->ISR, USART_ISR_RTOF) == (USART_ISR_RTOF));
2653 * @brief Check if the USART End Of Block Flag is set or not
2654 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2655 * Smartcard feature is supported by the USARTx instance.
2656 * @rmtoll ISR EOBF LL_USART_IsActiveFlag_EOB
2657 * @param USARTx USART Instance
2658 * @retval State of bit (1 or 0).
2660 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_EOB(USART_TypeDef *USARTx)
2662 return (READ_BIT(USARTx->ISR, USART_ISR_EOBF) == (USART_ISR_EOBF));
2666 * @brief Check if the USART Auto-Baud Rate Error Flag is set or not
2667 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2668 * Auto Baud Rate detection feature is supported by the USARTx instance.
2669 * @rmtoll ISR ABRE LL_USART_IsActiveFlag_ABRE
2670 * @param USARTx USART Instance
2671 * @retval State of bit (1 or 0).
2673 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ABRE(USART_TypeDef *USARTx)
2675 return (READ_BIT(USARTx->ISR, USART_ISR_ABRE) == (USART_ISR_ABRE));
2679 * @brief Check if the USART Auto-Baud Rate Flag is set or not
2680 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2681 * Auto Baud Rate detection feature is supported by the USARTx instance.
2682 * @rmtoll ISR ABRF LL_USART_IsActiveFlag_ABR
2683 * @param USARTx USART Instance
2684 * @retval State of bit (1 or 0).
2686 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ABR(USART_TypeDef *USARTx)
2688 return (READ_BIT(USARTx->ISR, USART_ISR_ABRF) == (USART_ISR_ABRF));
2692 * @brief Check if the USART Busy Flag is set or not
2693 * @rmtoll ISR BUSY LL_USART_IsActiveFlag_BUSY
2694 * @param USARTx USART Instance
2695 * @retval State of bit (1 or 0).
2697 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_BUSY(USART_TypeDef *USARTx)
2699 return (READ_BIT(USARTx->ISR, USART_ISR_BUSY) == (USART_ISR_BUSY));
2703 * @brief Check if the USART Character Match Flag is set or not
2704 * @rmtoll ISR CMF LL_USART_IsActiveFlag_CM
2705 * @param USARTx USART Instance
2706 * @retval State of bit (1 or 0).
2708 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_CM(USART_TypeDef *USARTx)
2710 return (READ_BIT(USARTx->ISR, USART_ISR_CMF) == (USART_ISR_CMF));
2714 * @brief Check if the USART Send Break Flag is set or not
2715 * @rmtoll ISR SBKF LL_USART_IsActiveFlag_SBK
2716 * @param USARTx USART Instance
2717 * @retval State of bit (1 or 0).
2719 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx)
2721 return (READ_BIT(USARTx->ISR, USART_ISR_SBKF) == (USART_ISR_SBKF));
2725 * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not
2726 * @rmtoll ISR RWU LL_USART_IsActiveFlag_RWU
2727 * @param USARTx USART Instance
2728 * @retval State of bit (1 or 0).
2730 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx)
2732 return (READ_BIT(USARTx->ISR, USART_ISR_RWU) == (USART_ISR_RWU));
2736 * @brief Check if the USART Wake Up from stop mode Flag is set or not
2737 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
2738 * Wake-up from Stop mode feature is supported by the USARTx instance.
2739 * @rmtoll ISR WUF LL_USART_IsActiveFlag_WKUP
2740 * @param USARTx USART Instance
2741 * @retval State of bit (1 or 0).
2743 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_WKUP(USART_TypeDef *USARTx)
2745 return (READ_BIT(USARTx->ISR, USART_ISR_WUF) == (USART_ISR_WUF));
2749 * @brief Check if the USART Transmit Enable Acknowledge Flag is set or not
2750 * @rmtoll ISR TEACK LL_USART_IsActiveFlag_TEACK
2751 * @param USARTx USART Instance
2752 * @retval State of bit (1 or 0).
2754 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TEACK(USART_TypeDef *USARTx)
2756 return (READ_BIT(USARTx->ISR, USART_ISR_TEACK) == (USART_ISR_TEACK));
2760 * @brief Check if the USART Receive Enable Acknowledge Flag is set or not
2761 * @rmtoll ISR REACK LL_USART_IsActiveFlag_REACK
2762 * @param USARTx USART Instance
2763 * @retval State of bit (1 or 0).
2765 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_REACK(USART_TypeDef *USARTx)
2767 return (READ_BIT(USARTx->ISR, USART_ISR_REACK) == (USART_ISR_REACK));
2772 * @brief Clear Parity Error Flag
2773 * @rmtoll ICR PECF LL_USART_ClearFlag_PE
2774 * @param USARTx USART Instance
2775 * @retval None
2777 __STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx)
2779 WRITE_REG(USARTx->ICR, USART_ICR_PECF);
2783 * @brief Clear Framing Error Flag
2784 * @rmtoll ICR FECF LL_USART_ClearFlag_FE
2785 * @param USARTx USART Instance
2786 * @retval None
2788 __STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx)
2790 WRITE_REG(USARTx->ICR, USART_ICR_FECF);
2794 * @brief Clear Noise detected Flag
2795 * @rmtoll ICR NCF LL_USART_ClearFlag_NE
2796 * @param USARTx USART Instance
2797 * @retval None
2799 __STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx)
2801 WRITE_REG(USARTx->ICR, USART_ICR_NCF);
2805 * @brief Clear OverRun Error Flag
2806 * @rmtoll ICR ORECF LL_USART_ClearFlag_ORE
2807 * @param USARTx USART Instance
2808 * @retval None
2810 __STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx)
2812 WRITE_REG(USARTx->ICR, USART_ICR_ORECF);
2816 * @brief Clear IDLE line detected Flag
2817 * @rmtoll ICR IDLECF LL_USART_ClearFlag_IDLE
2818 * @param USARTx USART Instance
2819 * @retval None
2821 __STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx)
2823 WRITE_REG(USARTx->ICR, USART_ICR_IDLECF);
2827 * @brief Clear Transmission Complete Flag
2828 * @rmtoll ICR TCCF LL_USART_ClearFlag_TC
2829 * @param USARTx USART Instance
2830 * @retval None
2832 __STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx)
2834 WRITE_REG(USARTx->ICR, USART_ICR_TCCF);
2839 * @brief Clear LIN Break Detection Flag
2840 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2841 * LIN feature is supported by the USARTx instance.
2842 * @rmtoll ICR LBDCF LL_USART_ClearFlag_LBD
2843 * @param USARTx USART Instance
2844 * @retval None
2846 __STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx)
2848 WRITE_REG(USARTx->ICR, USART_ICR_LBDCF);
2852 * @brief Clear CTS Interrupt Flag
2853 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2854 * Hardware Flow control feature is supported by the USARTx instance.
2855 * @rmtoll ICR CTSCF LL_USART_ClearFlag_nCTS
2856 * @param USARTx USART Instance
2857 * @retval None
2859 __STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx)
2861 WRITE_REG(USARTx->ICR, USART_ICR_CTSCF);
2865 * @brief Clear Receiver Time Out Flag
2866 * @rmtoll ICR RTOCF LL_USART_ClearFlag_RTO
2867 * @param USARTx USART Instance
2868 * @retval None
2870 __STATIC_INLINE void LL_USART_ClearFlag_RTO(USART_TypeDef *USARTx)
2872 WRITE_REG(USARTx->ICR, USART_ICR_RTOCF);
2876 * @brief Clear End Of Block Flag
2877 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2878 * Smartcard feature is supported by the USARTx instance.
2879 * @rmtoll ICR EOBCF LL_USART_ClearFlag_EOB
2880 * @param USARTx USART Instance
2881 * @retval None
2883 __STATIC_INLINE void LL_USART_ClearFlag_EOB(USART_TypeDef *USARTx)
2885 WRITE_REG(USARTx->ICR, USART_ICR_EOBCF);
2889 * @brief Clear Character Match Flag
2890 * @rmtoll ICR CMCF LL_USART_ClearFlag_CM
2891 * @param USARTx USART Instance
2892 * @retval None
2894 __STATIC_INLINE void LL_USART_ClearFlag_CM(USART_TypeDef *USARTx)
2896 WRITE_REG(USARTx->ICR, USART_ICR_CMCF);
2900 * @brief Clear Wake Up from stop mode Flag
2901 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
2902 * Wake-up from Stop mode feature is supported by the USARTx instance.
2903 * @rmtoll ICR WUCF LL_USART_ClearFlag_WKUP
2904 * @param USARTx USART Instance
2905 * @retval None
2907 __STATIC_INLINE void LL_USART_ClearFlag_WKUP(USART_TypeDef *USARTx)
2909 WRITE_REG(USARTx->ICR, USART_ICR_WUCF);
2913 * @}
2916 /** @defgroup USART_LL_EF_IT_Management IT_Management
2917 * @{
2921 * @brief Enable IDLE Interrupt
2922 * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE
2923 * @param USARTx USART Instance
2924 * @retval None
2926 __STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx)
2928 SET_BIT(USARTx->CR1, USART_CR1_IDLEIE);
2932 * @brief Enable RX Not Empty Interrupt
2933 * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE
2934 * @param USARTx USART Instance
2935 * @retval None
2937 __STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx)
2939 SET_BIT(USARTx->CR1, USART_CR1_RXNEIE);
2943 * @brief Enable Transmission Complete Interrupt
2944 * @rmtoll CR1 TCIE LL_USART_EnableIT_TC
2945 * @param USARTx USART Instance
2946 * @retval None
2948 __STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx)
2950 SET_BIT(USARTx->CR1, USART_CR1_TCIE);
2954 * @brief Enable TX Empty Interrupt
2955 * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE
2956 * @param USARTx USART Instance
2957 * @retval None
2959 __STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx)
2961 SET_BIT(USARTx->CR1, USART_CR1_TXEIE);
2965 * @brief Enable Parity Error Interrupt
2966 * @rmtoll CR1 PEIE LL_USART_EnableIT_PE
2967 * @param USARTx USART Instance
2968 * @retval None
2970 __STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx)
2972 SET_BIT(USARTx->CR1, USART_CR1_PEIE);
2976 * @brief Enable Character Match Interrupt
2977 * @rmtoll CR1 CMIE LL_USART_EnableIT_CM
2978 * @param USARTx USART Instance
2979 * @retval None
2981 __STATIC_INLINE void LL_USART_EnableIT_CM(USART_TypeDef *USARTx)
2983 SET_BIT(USARTx->CR1, USART_CR1_CMIE);
2987 * @brief Enable Receiver Timeout Interrupt
2988 * @rmtoll CR1 RTOIE LL_USART_EnableIT_RTO
2989 * @param USARTx USART Instance
2990 * @retval None
2992 __STATIC_INLINE void LL_USART_EnableIT_RTO(USART_TypeDef *USARTx)
2994 SET_BIT(USARTx->CR1, USART_CR1_RTOIE);
2998 * @brief Enable End Of Block Interrupt
2999 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3000 * Smartcard feature is supported by the USARTx instance.
3001 * @rmtoll CR1 EOBIE LL_USART_EnableIT_EOB
3002 * @param USARTx USART Instance
3003 * @retval None
3005 __STATIC_INLINE void LL_USART_EnableIT_EOB(USART_TypeDef *USARTx)
3007 SET_BIT(USARTx->CR1, USART_CR1_EOBIE);
3011 * @brief Enable LIN Break Detection Interrupt
3012 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3013 * LIN feature is supported by the USARTx instance.
3014 * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD
3015 * @param USARTx USART Instance
3016 * @retval None
3018 __STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx)
3020 SET_BIT(USARTx->CR2, USART_CR2_LBDIE);
3024 * @brief Enable Error Interrupt
3025 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3026 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3027 * 0: Interrupt is inhibited
3028 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3029 * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR
3030 * @param USARTx USART Instance
3031 * @retval None
3033 __STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx)
3035 SET_BIT(USARTx->CR3, USART_CR3_EIE);
3039 * @brief Enable CTS Interrupt
3040 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3041 * Hardware Flow control feature is supported by the USARTx instance.
3042 * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS
3043 * @param USARTx USART Instance
3044 * @retval None
3046 __STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx)
3048 SET_BIT(USARTx->CR3, USART_CR3_CTSIE);
3052 * @brief Enable Wake Up from Stop Mode Interrupt
3053 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3054 * Wake-up from Stop mode feature is supported by the USARTx instance.
3055 * @rmtoll CR3 WUFIE LL_USART_EnableIT_WKUP
3056 * @param USARTx USART Instance
3057 * @retval None
3059 __STATIC_INLINE void LL_USART_EnableIT_WKUP(USART_TypeDef *USARTx)
3061 SET_BIT(USARTx->CR3, USART_CR3_WUFIE);
3066 * @brief Disable IDLE Interrupt
3067 * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE
3068 * @param USARTx USART Instance
3069 * @retval None
3071 __STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx)
3073 CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE);
3077 * @brief Disable RX Not Empty Interrupt
3078 * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE
3079 * @param USARTx USART Instance
3080 * @retval None
3082 __STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx)
3084 CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE);
3088 * @brief Disable Transmission Complete Interrupt
3089 * @rmtoll CR1 TCIE LL_USART_DisableIT_TC
3090 * @param USARTx USART Instance
3091 * @retval None
3093 __STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx)
3095 CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE);
3099 * @brief Disable TX Empty Interrupt
3100 * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE
3101 * @param USARTx USART Instance
3102 * @retval None
3104 __STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx)
3106 CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE);
3110 * @brief Disable Parity Error Interrupt
3111 * @rmtoll CR1 PEIE LL_USART_DisableIT_PE
3112 * @param USARTx USART Instance
3113 * @retval None
3115 __STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx)
3117 CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE);
3121 * @brief Disable Character Match Interrupt
3122 * @rmtoll CR1 CMIE LL_USART_DisableIT_CM
3123 * @param USARTx USART Instance
3124 * @retval None
3126 __STATIC_INLINE void LL_USART_DisableIT_CM(USART_TypeDef *USARTx)
3128 CLEAR_BIT(USARTx->CR1, USART_CR1_CMIE);
3132 * @brief Disable Receiver Timeout Interrupt
3133 * @rmtoll CR1 RTOIE LL_USART_DisableIT_RTO
3134 * @param USARTx USART Instance
3135 * @retval None
3137 __STATIC_INLINE void LL_USART_DisableIT_RTO(USART_TypeDef *USARTx)
3139 CLEAR_BIT(USARTx->CR1, USART_CR1_RTOIE);
3143 * @brief Disable End Of Block Interrupt
3144 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3145 * Smartcard feature is supported by the USARTx instance.
3146 * @rmtoll CR1 EOBIE LL_USART_DisableIT_EOB
3147 * @param USARTx USART Instance
3148 * @retval None
3150 __STATIC_INLINE void LL_USART_DisableIT_EOB(USART_TypeDef *USARTx)
3152 CLEAR_BIT(USARTx->CR1, USART_CR1_EOBIE);
3156 * @brief Disable LIN Break Detection Interrupt
3157 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3158 * LIN feature is supported by the USARTx instance.
3159 * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD
3160 * @param USARTx USART Instance
3161 * @retval None
3163 __STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx)
3165 CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE);
3169 * @brief Disable Error Interrupt
3170 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3171 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3172 * 0: Interrupt is inhibited
3173 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3174 * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR
3175 * @param USARTx USART Instance
3176 * @retval None
3178 __STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx)
3180 CLEAR_BIT(USARTx->CR3, USART_CR3_EIE);
3184 * @brief Disable CTS Interrupt
3185 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3186 * Hardware Flow control feature is supported by the USARTx instance.
3187 * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS
3188 * @param USARTx USART Instance
3189 * @retval None
3191 __STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx)
3193 CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE);
3197 * @brief Disable Wake Up from Stop Mode Interrupt
3198 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3199 * Wake-up from Stop mode feature is supported by the USARTx instance.
3200 * @rmtoll CR3 WUFIE LL_USART_DisableIT_WKUP
3201 * @param USARTx USART Instance
3202 * @retval None
3204 __STATIC_INLINE void LL_USART_DisableIT_WKUP(USART_TypeDef *USARTx)
3206 CLEAR_BIT(USARTx->CR3, USART_CR3_WUFIE);
3211 * @brief Check if the USART IDLE Interrupt source is enabled or disabled.
3212 * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE
3213 * @param USARTx USART Instance
3214 * @retval State of bit (1 or 0).
3216 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx)
3218 return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE));
3222 * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled.
3223 * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE
3224 * @param USARTx USART Instance
3225 * @retval State of bit (1 or 0).
3227 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx)
3229 return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE));
3233 * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled.
3234 * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC
3235 * @param USARTx USART Instance
3236 * @retval State of bit (1 or 0).
3238 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx)
3240 return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE));
3244 * @brief Check if the USART TX Empty Interrupt is enabled or disabled.
3245 * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE
3246 * @param USARTx USART Instance
3247 * @retval State of bit (1 or 0).
3249 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx)
3251 return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE));
3255 * @brief Check if the USART Parity Error Interrupt is enabled or disabled.
3256 * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE
3257 * @param USARTx USART Instance
3258 * @retval State of bit (1 or 0).
3260 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx)
3262 return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE));
3266 * @brief Check if the USART Character Match Interrupt is enabled or disabled.
3267 * @rmtoll CR1 CMIE LL_USART_IsEnabledIT_CM
3268 * @param USARTx USART Instance
3269 * @retval State of bit (1 or 0).
3271 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CM(USART_TypeDef *USARTx)
3273 return (READ_BIT(USARTx->CR1, USART_CR1_CMIE) == (USART_CR1_CMIE));
3277 * @brief Check if the USART Receiver Timeout Interrupt is enabled or disabled.
3278 * @rmtoll CR1 RTOIE LL_USART_IsEnabledIT_RTO
3279 * @param USARTx USART Instance
3280 * @retval State of bit (1 or 0).
3282 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RTO(USART_TypeDef *USARTx)
3284 return (READ_BIT(USARTx->CR1, USART_CR1_RTOIE) == (USART_CR1_RTOIE));
3288 * @brief Check if the USART End Of Block Interrupt is enabled or disabled.
3289 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3290 * Smartcard feature is supported by the USARTx instance.
3291 * @rmtoll CR1 EOBIE LL_USART_IsEnabledIT_EOB
3292 * @param USARTx USART Instance
3293 * @retval State of bit (1 or 0).
3295 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_EOB(USART_TypeDef *USARTx)
3297 return (READ_BIT(USARTx->CR1, USART_CR1_EOBIE) == (USART_CR1_EOBIE));
3301 * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled.
3302 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3303 * LIN feature is supported by the USARTx instance.
3304 * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD
3305 * @param USARTx USART Instance
3306 * @retval State of bit (1 or 0).
3308 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx)
3310 return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE));
3314 * @brief Check if the USART Error Interrupt is enabled or disabled.
3315 * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR
3316 * @param USARTx USART Instance
3317 * @retval State of bit (1 or 0).
3319 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx)
3321 return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE));
3325 * @brief Check if the USART CTS Interrupt is enabled or disabled.
3326 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3327 * Hardware Flow control feature is supported by the USARTx instance.
3328 * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS
3329 * @param USARTx USART Instance
3330 * @retval State of bit (1 or 0).
3332 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx)
3334 return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE));
3338 * @brief Check if the USART Wake Up from Stop Mode Interrupt is enabled or disabled.
3339 * @note Macro @ref IS_UART_WAKEUP_FROMSTOP_INSTANCE(USARTx) can be used to check whether or not
3340 * Wake-up from Stop mode feature is supported by the USARTx instance.
3341 * @rmtoll CR3 WUFIE LL_USART_IsEnabledIT_WKUP
3342 * @param USARTx USART Instance
3343 * @retval State of bit (1 or 0).
3345 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_WKUP(USART_TypeDef *USARTx)
3347 return (READ_BIT(USARTx->CR3, USART_CR3_WUFIE) == (USART_CR3_WUFIE));
3352 * @}
3355 /** @defgroup USART_LL_EF_DMA_Management DMA_Management
3356 * @{
3360 * @brief Enable DMA Mode for reception
3361 * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX
3362 * @param USARTx USART Instance
3363 * @retval None
3365 __STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx)
3367 SET_BIT(USARTx->CR3, USART_CR3_DMAR);
3371 * @brief Disable DMA Mode for reception
3372 * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX
3373 * @param USARTx USART Instance
3374 * @retval None
3376 __STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx)
3378 CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR);
3382 * @brief Check if DMA Mode is enabled for reception
3383 * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX
3384 * @param USARTx USART Instance
3385 * @retval State of bit (1 or 0).
3387 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx)
3389 return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR));
3393 * @brief Enable DMA Mode for transmission
3394 * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX
3395 * @param USARTx USART Instance
3396 * @retval None
3398 __STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx)
3400 SET_BIT(USARTx->CR3, USART_CR3_DMAT);
3404 * @brief Disable DMA Mode for transmission
3405 * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX
3406 * @param USARTx USART Instance
3407 * @retval None
3409 __STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx)
3411 CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT);
3415 * @brief Check if DMA Mode is enabled for transmission
3416 * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX
3417 * @param USARTx USART Instance
3418 * @retval State of bit (1 or 0).
3420 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx)
3422 return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT));
3426 * @brief Enable DMA Disabling on Reception Error
3427 * @rmtoll CR3 DDRE LL_USART_EnableDMADeactOnRxErr
3428 * @param USARTx USART Instance
3429 * @retval None
3431 __STATIC_INLINE void LL_USART_EnableDMADeactOnRxErr(USART_TypeDef *USARTx)
3433 SET_BIT(USARTx->CR3, USART_CR3_DDRE);
3437 * @brief Disable DMA Disabling on Reception Error
3438 * @rmtoll CR3 DDRE LL_USART_DisableDMADeactOnRxErr
3439 * @param USARTx USART Instance
3440 * @retval None
3442 __STATIC_INLINE void LL_USART_DisableDMADeactOnRxErr(USART_TypeDef *USARTx)
3444 CLEAR_BIT(USARTx->CR3, USART_CR3_DDRE);
3448 * @brief Indicate if DMA Disabling on Reception Error is disabled
3449 * @rmtoll CR3 DDRE LL_USART_IsEnabledDMADeactOnRxErr
3450 * @param USARTx USART Instance
3451 * @retval State of bit (1 or 0).
3453 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMADeactOnRxErr(USART_TypeDef *USARTx)
3455 return (READ_BIT(USARTx->CR3, USART_CR3_DDRE) == (USART_CR3_DDRE));
3459 * @brief Get the data register address used for DMA transfer
3460 * @rmtoll RDR RDR LL_USART_DMA_GetRegAddr\n
3461 * @rmtoll TDR TDR LL_USART_DMA_GetRegAddr
3462 * @param USARTx USART Instance
3463 * @param Direction This parameter can be one of the following values:
3464 * @arg @ref LL_USART_DMA_REG_DATA_TRANSMIT
3465 * @arg @ref LL_USART_DMA_REG_DATA_RECEIVE
3466 * @retval Address of data register
3468 __STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx, uint32_t Direction)
3470 register uint32_t data_reg_addr = 0U;
3472 if (Direction == LL_USART_DMA_REG_DATA_TRANSMIT)
3474 /* return address of TDR register */
3475 data_reg_addr = (uint32_t) &(USARTx->TDR);
3477 else
3479 /* return address of RDR register */
3480 data_reg_addr = (uint32_t) &(USARTx->RDR);
3483 return data_reg_addr;
3487 * @}
3490 /** @defgroup USART_LL_EF_Data_Management Data_Management
3491 * @{
3495 * @brief Read Receiver Data register (Receive Data value, 8 bits)
3496 * @rmtoll RDR RDR LL_USART_ReceiveData8
3497 * @param USARTx USART Instance
3498 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
3500 __STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx)
3502 return (uint8_t)(READ_BIT(USARTx->RDR, USART_RDR_RDR));
3506 * @brief Read Receiver Data register (Receive Data value, 9 bits)
3507 * @rmtoll RDR RDR LL_USART_ReceiveData9
3508 * @param USARTx USART Instance
3509 * @retval Value between Min_Data=0x00 and Max_Data=0x1FF
3511 __STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx)
3513 return (uint16_t)(READ_BIT(USARTx->RDR, USART_RDR_RDR));
3517 * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits)
3518 * @rmtoll TDR TDR LL_USART_TransmitData8
3519 * @param USARTx USART Instance
3520 * @param Value between Min_Data=0x00 and Max_Data=0xFF
3521 * @retval None
3523 __STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value)
3525 USARTx->TDR = Value;
3529 * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits)
3530 * @rmtoll TDR TDR LL_USART_TransmitData9
3531 * @param USARTx USART Instance
3532 * @param Value between Min_Data=0x00 and Max_Data=0x1FF
3533 * @retval None
3535 __STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value)
3537 USARTx->TDR = Value & 0x1FFU;
3541 * @}
3544 /** @defgroup USART_LL_EF_Execution Execution
3545 * @{
3549 * @brief Request an Automatic Baud Rate measurement on next received data frame
3550 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
3551 * Auto Baud Rate detection feature is supported by the USARTx instance.
3552 * @rmtoll RQR ABRRQ LL_USART_RequestAutoBaudRate
3553 * @param USARTx USART Instance
3554 * @retval None
3556 __STATIC_INLINE void LL_USART_RequestAutoBaudRate(USART_TypeDef *USARTx)
3558 SET_BIT(USARTx->RQR, USART_RQR_ABRRQ);
3562 * @brief Request Break sending
3563 * @rmtoll RQR SBKRQ LL_USART_RequestBreakSending
3564 * @param USARTx USART Instance
3565 * @retval None
3567 __STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx)
3569 SET_BIT(USARTx->RQR, USART_RQR_SBKRQ);
3573 * @brief Put USART in mute mode and set the RWU flag
3574 * @rmtoll RQR MMRQ LL_USART_RequestEnterMuteMode
3575 * @param USARTx USART Instance
3576 * @retval None
3578 __STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx)
3580 SET_BIT(USARTx->RQR, USART_RQR_MMRQ);
3584 * @brief Request a Receive Data flush
3585 * @rmtoll RQR RXFRQ LL_USART_RequestRxDataFlush
3586 * @param USARTx USART Instance
3587 * @retval None
3589 __STATIC_INLINE void LL_USART_RequestRxDataFlush(USART_TypeDef *USARTx)
3591 SET_BIT(USARTx->RQR, USART_RQR_RXFRQ);
3595 * @brief Request a Transmit data flush
3596 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3597 * Smartcard feature is supported by the USARTx instance.
3598 * @rmtoll RQR TXFRQ LL_USART_RequestTxDataFlush
3599 * @param USARTx USART Instance
3600 * @retval None
3602 __STATIC_INLINE void LL_USART_RequestTxDataFlush(USART_TypeDef *USARTx)
3604 SET_BIT(USARTx->RQR, USART_RQR_TXFRQ);
3608 * @}
3611 #if defined(USE_FULL_LL_DRIVER)
3612 /** @defgroup USART_LL_EF_Init Initialization and de-initialization functions
3613 * @{
3615 ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx);
3616 ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct);
3617 void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct);
3618 ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct);
3619 void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct);
3621 * @}
3623 #endif /* USE_FULL_LL_DRIVER */
3626 * @}
3630 * @}
3633 #endif /* USART1 || USART2|| USART3 || UART4 || UART5 */
3636 * @}
3639 #ifdef __cplusplus
3641 #endif
3643 #endif /* __STM32F3xx_LL_USART_H */
3645 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/