Merge pull request #10592 from iNavFlight/MrD_Update-parameter-description
[inav.git] / lib / main / STM32F7 / Drivers / STM32F7xx_HAL_Driver / Inc / stm32f7xx_ll_usart.h
blob34fc793d17b24c6a577cb661769c360b10d88820
1 /**
2 ******************************************************************************
3 * @file stm32f7xx_ll_usart.h
4 * @author MCD Application Team
5 * @version V1.2.2
6 * @date 14-April-2017
7 * @brief Header file of USART LL module.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
13 * Redistribution and use in source and binary forms, with or without modification,
14 * are permitted provided that the following conditions are met:
15 * 1. Redistributions of source code must retain the above copyright notice,
16 * this list of conditions and the following disclaimer.
17 * 2. Redistributions in binary form must reproduce the above copyright notice,
18 * this list of conditions and the following disclaimer in the documentation
19 * and/or other materials provided with the distribution.
20 * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 * may be used to endorse or promote products derived from this software
22 * without specific prior written permission.
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 ******************************************************************************
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef __STM32F7xx_LL_USART_H
40 #define __STM32F7xx_LL_USART_H
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
46 /* Includes ------------------------------------------------------------------*/
47 #include "stm32f7xx.h"
49 /** @addtogroup STM32F7xx_LL_Driver
50 * @{
53 #if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8)
55 /** @defgroup USART_LL USART
56 * @{
59 /* Private types -------------------------------------------------------------*/
60 /* Private variables ---------------------------------------------------------*/
62 /* Private constants ---------------------------------------------------------*/
63 /** @defgroup USART_LL_Private_Constants USART Private Constants
64 * @{
66 /**
67 * @}
70 /* Private macros ------------------------------------------------------------*/
71 #if defined(USE_FULL_LL_DRIVER)
72 /** @defgroup USART_LL_Private_Macros USART Private Macros
73 * @{
75 /**
76 * @}
78 #endif /*USE_FULL_LL_DRIVER*/
80 /* Exported types ------------------------------------------------------------*/
81 #if defined(USE_FULL_LL_DRIVER)
82 /** @defgroup USART_LL_ES_INIT USART Exported Init structures
83 * @{
86 /**
87 * @brief LL USART Init Structure definition
89 typedef struct
91 uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate.
93 This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/
95 uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame.
96 This parameter can be a value of @ref USART_LL_EC_DATAWIDTH.
98 This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/
100 uint32_t StopBits; /*!< Specifies the number of stop bits transmitted.
101 This parameter can be a value of @ref USART_LL_EC_STOPBITS.
103 This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/
105 uint32_t Parity; /*!< Specifies the parity mode.
106 This parameter can be a value of @ref USART_LL_EC_PARITY.
108 This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/
110 uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled.
111 This parameter can be a value of @ref USART_LL_EC_DIRECTION.
113 This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/
115 uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled.
116 This parameter can be a value of @ref USART_LL_EC_HWCONTROL.
118 This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/
120 uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8.
121 This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING.
123 This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/
125 } LL_USART_InitTypeDef;
128 * @brief LL USART Clock Init Structure definition
130 typedef struct
132 uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled.
133 This parameter can be a value of @ref USART_LL_EC_CLOCK.
135 USART HW configuration can be modified afterwards using unitary functions
136 @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput().
137 For more details, refer to description of this function. */
139 uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock.
140 This parameter can be a value of @ref USART_LL_EC_POLARITY.
142 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity().
143 For more details, refer to description of this function. */
145 uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made.
146 This parameter can be a value of @ref USART_LL_EC_PHASE.
148 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase().
149 For more details, refer to description of this function. */
151 uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted
152 data bit (MSB) has to be output on the SCLK pin in synchronous mode.
153 This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE.
155 USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput().
156 For more details, refer to description of this function. */
158 } LL_USART_ClockInitTypeDef;
161 * @}
163 #endif /* USE_FULL_LL_DRIVER */
165 /* Exported constants --------------------------------------------------------*/
166 /** @defgroup USART_LL_Exported_Constants USART Exported Constants
167 * @{
170 /** @defgroup USART_LL_EC_CLEAR_FLAG Clear Flags Defines
171 * @brief Flags defines which can be used with LL_USART_WriteReg function
172 * @{
174 #define LL_USART_ICR_PECF USART_ICR_PECF /*!< Parity error flag */
175 #define LL_USART_ICR_FECF USART_ICR_FECF /*!< Framing error flag */
176 #define LL_USART_ICR_NCF USART_ICR_NCF /*!< Noise detected flag */
177 #define LL_USART_ICR_ORECF USART_ICR_ORECF /*!< Overrun error flag */
178 #define LL_USART_ICR_IDLECF USART_ICR_IDLECF /*!< Idle line detected flag */
179 #define LL_USART_ICR_TCCF USART_ICR_TCCF /*!< Transmission complete flag */
180 #if defined(USART_TCBGT_SUPPORT)
181 #define LL_USART_ICR_TCBGTCF USART_ICR_TCBGTCF /*!< Transmission completed before guard time flag */
182 #endif
183 #define LL_USART_ICR_LBDCF USART_ICR_LBDCF /*!< LIN break detection flag */
184 #define LL_USART_ICR_CTSCF USART_ICR_CTSCF /*!< CTS flag */
185 #define LL_USART_ICR_RTOCF USART_ICR_RTOCF /*!< Receiver timeout flag */
186 #define LL_USART_ICR_EOBCF USART_ICR_EOBCF /*!< End of block flag */
187 #define LL_USART_ICR_CMCF USART_ICR_CMCF /*!< Character match flag */
189 * @}
192 /** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines
193 * @brief Flags defines which can be used with LL_USART_ReadReg function
194 * @{
196 #define LL_USART_ISR_PE USART_ISR_PE /*!< Parity error flag */
197 #define LL_USART_ISR_FE USART_ISR_FE /*!< Framing error flag */
198 #define LL_USART_ISR_NE USART_ISR_NE /*!< Noise detected flag */
199 #define LL_USART_ISR_ORE USART_ISR_ORE /*!< Overrun error flag */
200 #define LL_USART_ISR_IDLE USART_ISR_IDLE /*!< Idle line detected flag */
201 #define LL_USART_ISR_RXNE USART_ISR_RXNE /*!< Read data register not empty flag */
202 #define LL_USART_ISR_TC USART_ISR_TC /*!< Transmission complete flag */
203 #define LL_USART_ISR_TXE USART_ISR_TXE /*!< Transmit data register empty flag */
204 #define LL_USART_ISR_LBDF USART_ISR_LBDF /*!< LIN break detection flag */
205 #define LL_USART_ISR_CTSIF USART_ISR_CTSIF /*!< CTS interrupt flag */
206 #define LL_USART_ISR_CTS USART_ISR_CTS /*!< CTS flag */
207 #define LL_USART_ISR_RTOF USART_ISR_RTOF /*!< Receiver timeout flag */
208 #define LL_USART_ISR_EOBF USART_ISR_EOBF /*!< End of block flag */
209 #define LL_USART_ISR_ABRE USART_ISR_ABRE /*!< Auto baud rate error flag */
210 #define LL_USART_ISR_ABRF USART_ISR_ABRF /*!< Auto baud rate flag */
211 #define LL_USART_ISR_BUSY USART_ISR_BUSY /*!< Busy flag */
212 #define LL_USART_ISR_CMF USART_ISR_CMF /*!< Character match flag */
213 #define LL_USART_ISR_SBKF USART_ISR_SBKF /*!< Send break flag */
214 #define LL_USART_ISR_RWU USART_ISR_RWU /*!< Receiver wakeup from Mute mode flag */
215 #define LL_USART_ISR_TEACK USART_ISR_TEACK /*!< Transmit enable acknowledge flag */
216 #if defined(USART_TCBGT_SUPPORT)
217 #define LL_USART_ISR_TCBGT USART_ISR_TCBGT /*!< Transmission complete before guard time completion flag */
218 #endif
220 * @}
223 /** @defgroup USART_LL_EC_IT IT Defines
224 * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions
225 * @{
227 #define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */
228 #define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */
229 #define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */
230 #define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */
231 #define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */
232 #define LL_USART_CR1_CMIE USART_CR1_CMIE /*!< Character match interrupt enable */
233 #define LL_USART_CR1_RTOIE USART_CR1_RTOIE /*!< Receiver timeout interrupt enable */
234 #define LL_USART_CR1_EOBIE USART_CR1_EOBIE /*!< End of Block interrupt enable */
235 #define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */
236 #define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */
237 #define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */
238 #if defined(USART_TCBGT_SUPPORT)
239 #define LL_USART_CR3_TCBGTIE USART_CR3_TCBGTIE /*!< Transmission complete before guard time interrupt enable */
240 #endif
242 * @}
245 /** @defgroup USART_LL_EC_DIRECTION Communication Direction
246 * @{
248 #define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */
249 #define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */
250 #define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */
251 #define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */
253 * @}
256 /** @defgroup USART_LL_EC_PARITY Parity Control
257 * @{
259 #define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */
260 #define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */
261 #define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */
263 * @}
266 /** @defgroup USART_LL_EC_WAKEUP Wakeup
267 * @{
269 #define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */
270 #define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */
272 * @}
275 /** @defgroup USART_LL_EC_DATAWIDTH Datawidth
276 * @{
278 #define LL_USART_DATAWIDTH_7B USART_CR1_M1 /*!< 7 bits word length : Start bit, 7 data bits, n stop bits */
279 #define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */
280 #define LL_USART_DATAWIDTH_9B USART_CR1_M0 /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */
282 * @}
285 /** @defgroup USART_LL_EC_OVERSAMPLING Oversampling
286 * @{
288 #define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */
289 #define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */
291 * @}
294 #if defined(USE_FULL_LL_DRIVER)
295 /** @defgroup USART_LL_EC_CLOCK Clock Signal
296 * @{
299 #define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */
300 #define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */
302 * @}
304 #endif /*USE_FULL_LL_DRIVER*/
306 /** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse
307 * @{
309 #define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */
310 #define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */
312 * @}
315 /** @defgroup USART_LL_EC_PHASE Clock Phase
316 * @{
318 #define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */
319 #define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */
321 * @}
324 /** @defgroup USART_LL_EC_POLARITY Clock Polarity
325 * @{
327 #define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/
328 #define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */
330 * @}
333 /** @defgroup USART_LL_EC_STOPBITS Stop Bits
334 * @{
336 #define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */
337 #define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */
338 #define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */
339 #define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */
341 * @}
344 /** @defgroup USART_LL_EC_TXRX TX RX Pins Swap
345 * @{
347 #define LL_USART_TXRX_STANDARD 0x00000000U /*!< TX/RX pins are used as defined in standard pinout */
348 #define LL_USART_TXRX_SWAPPED (USART_CR2_SWAP) /*!< TX and RX pins functions are swapped. */
350 * @}
353 /** @defgroup USART_LL_EC_RXPIN_LEVEL RX Pin Active Level Inversion
354 * @{
356 #define LL_USART_RXPIN_LEVEL_STANDARD 0x00000000U /*!< RX pin signal works using the standard logic levels */
357 #define LL_USART_RXPIN_LEVEL_INVERTED (USART_CR2_RXINV) /*!< RX pin signal values are inverted. */
359 * @}
362 /** @defgroup USART_LL_EC_TXPIN_LEVEL TX Pin Active Level Inversion
363 * @{
365 #define LL_USART_TXPIN_LEVEL_STANDARD 0x00000000U /*!< TX pin signal works using the standard logic levels */
366 #define LL_USART_TXPIN_LEVEL_INVERTED (USART_CR2_TXINV) /*!< TX pin signal values are inverted. */
368 * @}
371 /** @defgroup USART_LL_EC_BINARY_LOGIC Binary Data Inversion
372 * @{
374 #define LL_USART_BINARY_LOGIC_POSITIVE 0x00000000U /*!< Logical data from the data register are send/received in positive/direct logic. (1=H, 0=L) */
375 #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. */
377 * @}
380 /** @defgroup USART_LL_EC_BITORDER Bit Order
381 * @{
383 #define LL_USART_BITORDER_LSBFIRST 0x00000000U /*!< data is transmitted/received with data bit 0 first, following the start bit */
384 #define LL_USART_BITORDER_MSBFIRST USART_CR2_MSBFIRST /*!< data is transmitted/received with the MSB first, following the start bit */
386 * @}
389 /** @defgroup USART_LL_EC_AUTOBAUD_DETECT_ON Autobaud Detection
390 * @{
392 #define LL_USART_AUTOBAUD_DETECT_ON_STARTBIT 0x00000000U /*!< Measurement of the start bit is used to detect the baud rate */
393 #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 */
394 #define LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME USART_CR2_ABRMODE_1 /*!< 0x7F frame detection */
395 #define LL_USART_AUTOBAUD_DETECT_ON_55_FRAME (USART_CR2_ABRMODE_1 | USART_CR2_ABRMODE_0) /*!< 0x55 frame detection */
397 * @}
400 /** @defgroup USART_LL_EC_ADDRESS_DETECT Address Length Detection
401 * @{
403 #define LL_USART_ADDRESS_DETECT_4B 0x00000000U /*!< 4-bit address detection method selected */
404 #define LL_USART_ADDRESS_DETECT_7B USART_CR2_ADDM7 /*!< 7-bit address detection (in 8-bit data mode) method selected */
406 * @}
409 /** @defgroup USART_LL_EC_HWCONTROL Hardware Control
410 * @{
412 #define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */
413 #define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */
414 #define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */
415 #define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */
417 * @}
421 /** @defgroup USART_LL_EC_IRDA_POWER IrDA Power
422 * @{
424 #define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */
425 #define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */
427 * @}
430 /** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length
431 * @{
433 #define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */
434 #define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */
436 * @}
439 /** @defgroup USART_LL_EC_DE_POLARITY Driver Enable Polarity
440 * @{
442 #define LL_USART_DE_POLARITY_HIGH 0x00000000U /*!< DE signal is active high */
443 #define LL_USART_DE_POLARITY_LOW USART_CR3_DEP /*!< DE signal is active low */
445 * @}
448 /** @defgroup USART_LL_EC_DMA_REG_DATA DMA Register Data
449 * @{
451 #define LL_USART_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for transmission */
452 #define LL_USART_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for reception */
454 * @}
458 * @}
461 /* Exported macro ------------------------------------------------------------*/
462 /** @defgroup USART_LL_Exported_Macros USART Exported Macros
463 * @{
466 /** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros
467 * @{
471 * @brief Write a value in USART register
472 * @param __INSTANCE__ USART Instance
473 * @param __REG__ Register to be written
474 * @param __VALUE__ Value to be written in the register
475 * @retval None
477 #define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__))
480 * @brief Read a value in USART register
481 * @param __INSTANCE__ USART Instance
482 * @param __REG__ Register to be read
483 * @retval Register value
485 #define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__)
487 * @}
490 /** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper
491 * @{
495 * @brief Compute USARTDIV value according to Peripheral Clock and
496 * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned)
497 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
498 * @param __BAUDRATE__ Baud rate value to achieve
499 * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case
501 #define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__PERIPHCLK__)*2) + ((__BAUDRATE__)/2))/(__BAUDRATE__))
504 * @brief Compute USARTDIV value according to Peripheral Clock and
505 * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned)
506 * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance
507 * @param __BAUDRATE__ Baud rate value to achieve
508 * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case
510 #define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__PERIPHCLK__) + ((__BAUDRATE__)/2))/(__BAUDRATE__))
513 * @}
517 * @}
520 /* Exported functions --------------------------------------------------------*/
522 /** @defgroup USART_LL_Exported_Functions USART Exported Functions
523 * @{
526 /** @defgroup USART_LL_EF_Configuration Configuration functions
527 * @{
531 * @brief USART Enable
532 * @rmtoll CR1 UE LL_USART_Enable
533 * @param USARTx USART Instance
534 * @retval None
536 __STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx)
538 SET_BIT(USARTx->CR1, USART_CR1_UE);
542 * @brief USART Disable (all USART prescalers and outputs are disabled)
543 * @note When USART is disabled, USART prescalers and outputs are stopped immediately,
544 * and current operations are discarded. The configuration of the USART is kept, but all the status
545 * flags, in the USARTx_ISR are set to their default values.
546 * @rmtoll CR1 UE LL_USART_Disable
547 * @param USARTx USART Instance
548 * @retval None
550 __STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx)
552 CLEAR_BIT(USARTx->CR1, USART_CR1_UE);
556 * @brief Indicate if USART is enabled
557 * @rmtoll CR1 UE LL_USART_IsEnabled
558 * @param USARTx USART Instance
559 * @retval State of bit (1 or 0).
561 __STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx)
563 return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE));
568 * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit)
569 * @rmtoll CR1 RE LL_USART_EnableDirectionRx
570 * @param USARTx USART Instance
571 * @retval None
573 __STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx)
575 SET_BIT(USARTx->CR1, USART_CR1_RE);
579 * @brief Receiver Disable
580 * @rmtoll CR1 RE LL_USART_DisableDirectionRx
581 * @param USARTx USART Instance
582 * @retval None
584 __STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx)
586 CLEAR_BIT(USARTx->CR1, USART_CR1_RE);
590 * @brief Transmitter Enable
591 * @rmtoll CR1 TE LL_USART_EnableDirectionTx
592 * @param USARTx USART Instance
593 * @retval None
595 __STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx)
597 SET_BIT(USARTx->CR1, USART_CR1_TE);
601 * @brief Transmitter Disable
602 * @rmtoll CR1 TE LL_USART_DisableDirectionTx
603 * @param USARTx USART Instance
604 * @retval None
606 __STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx)
608 CLEAR_BIT(USARTx->CR1, USART_CR1_TE);
612 * @brief Configure simultaneously enabled/disabled states
613 * of Transmitter and Receiver
614 * @rmtoll CR1 RE LL_USART_SetTransferDirection\n
615 * CR1 TE LL_USART_SetTransferDirection
616 * @param USARTx USART Instance
617 * @param TransferDirection This parameter can be one of the following values:
618 * @arg @ref LL_USART_DIRECTION_NONE
619 * @arg @ref LL_USART_DIRECTION_RX
620 * @arg @ref LL_USART_DIRECTION_TX
621 * @arg @ref LL_USART_DIRECTION_TX_RX
622 * @retval None
624 __STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection)
626 MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection);
630 * @brief Return enabled/disabled states of Transmitter and Receiver
631 * @rmtoll CR1 RE LL_USART_GetTransferDirection\n
632 * CR1 TE LL_USART_GetTransferDirection
633 * @param USARTx USART Instance
634 * @retval Returned value can be one of the following values:
635 * @arg @ref LL_USART_DIRECTION_NONE
636 * @arg @ref LL_USART_DIRECTION_RX
637 * @arg @ref LL_USART_DIRECTION_TX
638 * @arg @ref LL_USART_DIRECTION_TX_RX
640 __STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx)
642 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE));
646 * @brief Configure Parity (enabled/disabled and parity mode if enabled).
647 * @note This function selects if hardware parity control (generation and detection) is enabled or disabled.
648 * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position
649 * (9th or 8th bit depending on data width) and parity is checked on the received data.
650 * @rmtoll CR1 PS LL_USART_SetParity\n
651 * CR1 PCE LL_USART_SetParity
652 * @param USARTx USART Instance
653 * @param Parity This parameter can be one of the following values:
654 * @arg @ref LL_USART_PARITY_NONE
655 * @arg @ref LL_USART_PARITY_EVEN
656 * @arg @ref LL_USART_PARITY_ODD
657 * @retval None
659 __STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity)
661 MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity);
665 * @brief Return Parity configuration (enabled/disabled and parity mode if enabled)
666 * @rmtoll CR1 PS LL_USART_GetParity\n
667 * CR1 PCE LL_USART_GetParity
668 * @param USARTx USART Instance
669 * @retval Returned value can be one of the following values:
670 * @arg @ref LL_USART_PARITY_NONE
671 * @arg @ref LL_USART_PARITY_EVEN
672 * @arg @ref LL_USART_PARITY_ODD
674 __STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx)
676 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE));
680 * @brief Set Receiver Wake Up method from Mute mode.
681 * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod
682 * @param USARTx USART Instance
683 * @param Method This parameter can be one of the following values:
684 * @arg @ref LL_USART_WAKEUP_IDLELINE
685 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
686 * @retval None
688 __STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method)
690 MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method);
694 * @brief Return Receiver Wake Up method from Mute mode
695 * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod
696 * @param USARTx USART Instance
697 * @retval Returned value can be one of the following values:
698 * @arg @ref LL_USART_WAKEUP_IDLELINE
699 * @arg @ref LL_USART_WAKEUP_ADDRESSMARK
701 __STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx)
703 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE));
707 * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits)
708 * @rmtoll CR1 M0 LL_USART_SetDataWidth\n
709 * CR1 M1 LL_USART_SetDataWidth
710 * @param USARTx USART Instance
711 * @param DataWidth This parameter can be one of the following values:
712 * @arg @ref LL_USART_DATAWIDTH_7B
713 * @arg @ref LL_USART_DATAWIDTH_8B
714 * @arg @ref LL_USART_DATAWIDTH_9B
715 * @retval None
717 __STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth)
719 MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth);
723 * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits)
724 * @rmtoll CR1 M0 LL_USART_GetDataWidth\n
725 * CR1 M1 LL_USART_GetDataWidth
726 * @param USARTx USART Instance
727 * @retval Returned value can be one of the following values:
728 * @arg @ref LL_USART_DATAWIDTH_7B
729 * @arg @ref LL_USART_DATAWIDTH_8B
730 * @arg @ref LL_USART_DATAWIDTH_9B
732 __STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx)
734 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M));
738 * @brief Allow switch between Mute Mode and Active mode
739 * @rmtoll CR1 MME LL_USART_EnableMuteMode
740 * @param USARTx USART Instance
741 * @retval None
743 __STATIC_INLINE void LL_USART_EnableMuteMode(USART_TypeDef *USARTx)
745 SET_BIT(USARTx->CR1, USART_CR1_MME);
749 * @brief Prevent Mute Mode use. Set Receiver in active mode permanently.
750 * @rmtoll CR1 MME LL_USART_DisableMuteMode
751 * @param USARTx USART Instance
752 * @retval None
754 __STATIC_INLINE void LL_USART_DisableMuteMode(USART_TypeDef *USARTx)
756 CLEAR_BIT(USARTx->CR1, USART_CR1_MME);
760 * @brief Indicate if switch between Mute Mode and Active mode is allowed
761 * @rmtoll CR1 MME LL_USART_IsEnabledMuteMode
762 * @param USARTx USART Instance
763 * @retval State of bit (1 or 0).
765 __STATIC_INLINE uint32_t LL_USART_IsEnabledMuteMode(USART_TypeDef *USARTx)
767 return (READ_BIT(USARTx->CR1, USART_CR1_MME) == (USART_CR1_MME));
771 * @brief Set Oversampling to 8-bit or 16-bit mode
772 * @rmtoll CR1 OVER8 LL_USART_SetOverSampling
773 * @param USARTx USART Instance
774 * @param OverSampling This parameter can be one of the following values:
775 * @arg @ref LL_USART_OVERSAMPLING_16
776 * @arg @ref LL_USART_OVERSAMPLING_8
777 * @retval None
779 __STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling)
781 MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling);
785 * @brief Return Oversampling mode
786 * @rmtoll CR1 OVER8 LL_USART_GetOverSampling
787 * @param USARTx USART Instance
788 * @retval Returned value can be one of the following values:
789 * @arg @ref LL_USART_OVERSAMPLING_16
790 * @arg @ref LL_USART_OVERSAMPLING_8
792 __STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx)
794 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8));
798 * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not
799 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
800 * Synchronous mode is supported by the USARTx instance.
801 * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput
802 * @param USARTx USART Instance
803 * @param LastBitClockPulse This parameter can be one of the following values:
804 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
805 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
806 * @retval None
808 __STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse)
810 MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse);
814 * @brief Retrieve Clock pulse of the last data bit output configuration
815 * (Last bit Clock pulse output to the SCLK pin or not)
816 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
817 * Synchronous mode is supported by the USARTx instance.
818 * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput
819 * @param USARTx USART Instance
820 * @retval Returned value can be one of the following values:
821 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
822 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
824 __STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx)
826 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL));
830 * @brief Select the phase of the clock output on the SCLK pin in synchronous mode
831 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
832 * Synchronous mode is supported by the USARTx instance.
833 * @rmtoll CR2 CPHA LL_USART_SetClockPhase
834 * @param USARTx USART Instance
835 * @param ClockPhase This parameter can be one of the following values:
836 * @arg @ref LL_USART_PHASE_1EDGE
837 * @arg @ref LL_USART_PHASE_2EDGE
838 * @retval None
840 __STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase)
842 MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase);
846 * @brief Return phase of the clock output on the SCLK pin in synchronous mode
847 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
848 * Synchronous mode is supported by the USARTx instance.
849 * @rmtoll CR2 CPHA LL_USART_GetClockPhase
850 * @param USARTx USART Instance
851 * @retval Returned value can be one of the following values:
852 * @arg @ref LL_USART_PHASE_1EDGE
853 * @arg @ref LL_USART_PHASE_2EDGE
855 __STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx)
857 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA));
861 * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode
862 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
863 * Synchronous mode is supported by the USARTx instance.
864 * @rmtoll CR2 CPOL LL_USART_SetClockPolarity
865 * @param USARTx USART Instance
866 * @param ClockPolarity This parameter can be one of the following values:
867 * @arg @ref LL_USART_POLARITY_LOW
868 * @arg @ref LL_USART_POLARITY_HIGH
869 * @retval None
871 __STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity)
873 MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity);
877 * @brief Return polarity of the clock output on the SCLK pin in synchronous mode
878 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
879 * Synchronous mode is supported by the USARTx instance.
880 * @rmtoll CR2 CPOL LL_USART_GetClockPolarity
881 * @param USARTx USART Instance
882 * @retval Returned value can be one of the following values:
883 * @arg @ref LL_USART_POLARITY_LOW
884 * @arg @ref LL_USART_POLARITY_HIGH
886 __STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx)
888 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL));
892 * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse)
893 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
894 * Synchronous mode is supported by the USARTx instance.
895 * @note Call of this function is equivalent to following function call sequence :
896 * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function
897 * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function
898 * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function
899 * @rmtoll CR2 CPHA LL_USART_ConfigClock\n
900 * CR2 CPOL LL_USART_ConfigClock\n
901 * CR2 LBCL LL_USART_ConfigClock
902 * @param USARTx USART Instance
903 * @param Phase This parameter can be one of the following values:
904 * @arg @ref LL_USART_PHASE_1EDGE
905 * @arg @ref LL_USART_PHASE_2EDGE
906 * @param Polarity This parameter can be one of the following values:
907 * @arg @ref LL_USART_POLARITY_LOW
908 * @arg @ref LL_USART_POLARITY_HIGH
909 * @param LBCPOutput This parameter can be one of the following values:
910 * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT
911 * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT
912 * @retval None
914 __STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput)
916 MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput);
920 * @brief Enable Clock output on SCLK pin
921 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
922 * Synchronous mode is supported by the USARTx instance.
923 * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput
924 * @param USARTx USART Instance
925 * @retval None
927 __STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx)
929 SET_BIT(USARTx->CR2, USART_CR2_CLKEN);
933 * @brief Disable Clock output on SCLK pin
934 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
935 * Synchronous mode is supported by the USARTx instance.
936 * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput
937 * @param USARTx USART Instance
938 * @retval None
940 __STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx)
942 CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN);
946 * @brief Indicate if Clock output on SCLK pin is enabled
947 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
948 * Synchronous mode is supported by the USARTx instance.
949 * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput
950 * @param USARTx USART Instance
951 * @retval State of bit (1 or 0).
953 __STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx)
955 return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN));
959 * @brief Set the length of the stop bits
960 * @rmtoll CR2 STOP LL_USART_SetStopBitsLength
961 * @param USARTx USART Instance
962 * @param StopBits This parameter can be one of the following values:
963 * @arg @ref LL_USART_STOPBITS_0_5
964 * @arg @ref LL_USART_STOPBITS_1
965 * @arg @ref LL_USART_STOPBITS_1_5
966 * @arg @ref LL_USART_STOPBITS_2
967 * @retval None
969 __STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits)
971 MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits);
975 * @brief Retrieve the length of the stop bits
976 * @rmtoll CR2 STOP LL_USART_GetStopBitsLength
977 * @param USARTx USART Instance
978 * @retval Returned value can be one of the following values:
979 * @arg @ref LL_USART_STOPBITS_0_5
980 * @arg @ref LL_USART_STOPBITS_1
981 * @arg @ref LL_USART_STOPBITS_1_5
982 * @arg @ref LL_USART_STOPBITS_2
984 __STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx)
986 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP));
990 * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits)
991 * @note Call of this function is equivalent to following function call sequence :
992 * - Data Width configuration using @ref LL_USART_SetDataWidth() function
993 * - Parity Control and mode configuration using @ref LL_USART_SetParity() function
994 * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function
995 * @rmtoll CR1 PS LL_USART_ConfigCharacter\n
996 * CR1 PCE LL_USART_ConfigCharacter\n
997 * CR1 M0 LL_USART_ConfigCharacter\n
998 * CR1 M1 LL_USART_ConfigCharacter\n
999 * CR2 STOP LL_USART_ConfigCharacter
1000 * @param USARTx USART Instance
1001 * @param DataWidth This parameter can be one of the following values:
1002 * @arg @ref LL_USART_DATAWIDTH_7B
1003 * @arg @ref LL_USART_DATAWIDTH_8B
1004 * @arg @ref LL_USART_DATAWIDTH_9B
1005 * @param Parity This parameter can be one of the following values:
1006 * @arg @ref LL_USART_PARITY_NONE
1007 * @arg @ref LL_USART_PARITY_EVEN
1008 * @arg @ref LL_USART_PARITY_ODD
1009 * @param StopBits This parameter can be one of the following values:
1010 * @arg @ref LL_USART_STOPBITS_0_5
1011 * @arg @ref LL_USART_STOPBITS_1
1012 * @arg @ref LL_USART_STOPBITS_1_5
1013 * @arg @ref LL_USART_STOPBITS_2
1014 * @retval None
1016 __STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity,
1017 uint32_t StopBits)
1019 MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth);
1020 MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits);
1024 * @brief Configure TX/RX pins swapping setting.
1025 * @rmtoll CR2 SWAP LL_USART_SetTXRXSwap
1026 * @param USARTx USART Instance
1027 * @param SwapConfig This parameter can be one of the following values:
1028 * @arg @ref LL_USART_TXRX_STANDARD
1029 * @arg @ref LL_USART_TXRX_SWAPPED
1030 * @retval None
1032 __STATIC_INLINE void LL_USART_SetTXRXSwap(USART_TypeDef *USARTx, uint32_t SwapConfig)
1034 MODIFY_REG(USARTx->CR2, USART_CR2_SWAP, SwapConfig);
1038 * @brief Retrieve TX/RX pins swapping configuration.
1039 * @rmtoll CR2 SWAP LL_USART_GetTXRXSwap
1040 * @param USARTx USART Instance
1041 * @retval Returned value can be one of the following values:
1042 * @arg @ref LL_USART_TXRX_STANDARD
1043 * @arg @ref LL_USART_TXRX_SWAPPED
1045 __STATIC_INLINE uint32_t LL_USART_GetTXRXSwap(USART_TypeDef *USARTx)
1047 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_SWAP));
1051 * @brief Configure RX pin active level logic
1052 * @rmtoll CR2 RXINV LL_USART_SetRXPinLevel
1053 * @param USARTx USART Instance
1054 * @param PinInvMethod This parameter can be one of the following values:
1055 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1056 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1057 * @retval None
1059 __STATIC_INLINE void LL_USART_SetRXPinLevel(USART_TypeDef *USARTx, uint32_t PinInvMethod)
1061 MODIFY_REG(USARTx->CR2, USART_CR2_RXINV, PinInvMethod);
1065 * @brief Retrieve RX pin active level logic configuration
1066 * @rmtoll CR2 RXINV LL_USART_GetRXPinLevel
1067 * @param USARTx USART Instance
1068 * @retval Returned value can be one of the following values:
1069 * @arg @ref LL_USART_RXPIN_LEVEL_STANDARD
1070 * @arg @ref LL_USART_RXPIN_LEVEL_INVERTED
1072 __STATIC_INLINE uint32_t LL_USART_GetRXPinLevel(USART_TypeDef *USARTx)
1074 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_RXINV));
1078 * @brief Configure TX pin active level logic
1079 * @rmtoll CR2 TXINV LL_USART_SetTXPinLevel
1080 * @param USARTx USART Instance
1081 * @param PinInvMethod This parameter can be one of the following values:
1082 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1083 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1084 * @retval None
1086 __STATIC_INLINE void LL_USART_SetTXPinLevel(USART_TypeDef *USARTx, uint32_t PinInvMethod)
1088 MODIFY_REG(USARTx->CR2, USART_CR2_TXINV, PinInvMethod);
1092 * @brief Retrieve TX pin active level logic configuration
1093 * @rmtoll CR2 TXINV LL_USART_GetTXPinLevel
1094 * @param USARTx USART Instance
1095 * @retval Returned value can be one of the following values:
1096 * @arg @ref LL_USART_TXPIN_LEVEL_STANDARD
1097 * @arg @ref LL_USART_TXPIN_LEVEL_INVERTED
1099 __STATIC_INLINE uint32_t LL_USART_GetTXPinLevel(USART_TypeDef *USARTx)
1101 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_TXINV));
1105 * @brief Configure Binary data logic.
1106 * @note Allow to define how Logical data from the data register are send/received :
1107 * either in positive/direct logic (1=H, 0=L) or in negative/inverse logic (1=L, 0=H)
1108 * @rmtoll CR2 DATAINV LL_USART_SetBinaryDataLogic
1109 * @param USARTx USART Instance
1110 * @param DataLogic This parameter can be one of the following values:
1111 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1112 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1113 * @retval None
1115 __STATIC_INLINE void LL_USART_SetBinaryDataLogic(USART_TypeDef *USARTx, uint32_t DataLogic)
1117 MODIFY_REG(USARTx->CR2, USART_CR2_DATAINV, DataLogic);
1121 * @brief Retrieve Binary data configuration
1122 * @rmtoll CR2 DATAINV LL_USART_GetBinaryDataLogic
1123 * @param USARTx USART Instance
1124 * @retval Returned value can be one of the following values:
1125 * @arg @ref LL_USART_BINARY_LOGIC_POSITIVE
1126 * @arg @ref LL_USART_BINARY_LOGIC_NEGATIVE
1128 __STATIC_INLINE uint32_t LL_USART_GetBinaryDataLogic(USART_TypeDef *USARTx)
1130 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_DATAINV));
1134 * @brief Configure transfer bit order (either Less or Most Significant Bit First)
1135 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1136 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1137 * @rmtoll CR2 MSBFIRST LL_USART_SetTransferBitOrder
1138 * @param USARTx USART Instance
1139 * @param BitOrder This parameter can be one of the following values:
1140 * @arg @ref LL_USART_BITORDER_LSBFIRST
1141 * @arg @ref LL_USART_BITORDER_MSBFIRST
1142 * @retval None
1144 __STATIC_INLINE void LL_USART_SetTransferBitOrder(USART_TypeDef *USARTx, uint32_t BitOrder)
1146 MODIFY_REG(USARTx->CR2, USART_CR2_MSBFIRST, BitOrder);
1150 * @brief Return transfer bit order (either Less or Most Significant Bit First)
1151 * @note MSB First means data is transmitted/received with the MSB first, following the start bit.
1152 * LSB First means data is transmitted/received with data bit 0 first, following the start bit.
1153 * @rmtoll CR2 MSBFIRST LL_USART_GetTransferBitOrder
1154 * @param USARTx USART Instance
1155 * @retval Returned value can be one of the following values:
1156 * @arg @ref LL_USART_BITORDER_LSBFIRST
1157 * @arg @ref LL_USART_BITORDER_MSBFIRST
1159 __STATIC_INLINE uint32_t LL_USART_GetTransferBitOrder(USART_TypeDef *USARTx)
1161 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_MSBFIRST));
1165 * @brief Enable Auto Baud-Rate Detection
1166 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1167 * Auto Baud Rate detection feature is supported by the USARTx instance.
1168 * @rmtoll CR2 ABREN LL_USART_EnableAutoBaudRate
1169 * @param USARTx USART Instance
1170 * @retval None
1172 __STATIC_INLINE void LL_USART_EnableAutoBaudRate(USART_TypeDef *USARTx)
1174 SET_BIT(USARTx->CR2, USART_CR2_ABREN);
1178 * @brief Disable Auto Baud-Rate Detection
1179 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1180 * Auto Baud Rate detection feature is supported by the USARTx instance.
1181 * @rmtoll CR2 ABREN LL_USART_DisableAutoBaudRate
1182 * @param USARTx USART Instance
1183 * @retval None
1185 __STATIC_INLINE void LL_USART_DisableAutoBaudRate(USART_TypeDef *USARTx)
1187 CLEAR_BIT(USARTx->CR2, USART_CR2_ABREN);
1191 * @brief Indicate if Auto Baud-Rate Detection mechanism is enabled
1192 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1193 * Auto Baud Rate detection feature is supported by the USARTx instance.
1194 * @rmtoll CR2 ABREN LL_USART_IsEnabledAutoBaud
1195 * @param USARTx USART Instance
1196 * @retval State of bit (1 or 0).
1198 __STATIC_INLINE uint32_t LL_USART_IsEnabledAutoBaud(USART_TypeDef *USARTx)
1200 return (READ_BIT(USARTx->CR2, USART_CR2_ABREN) == (USART_CR2_ABREN));
1204 * @brief Set Auto Baud-Rate mode bits
1205 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1206 * Auto Baud Rate detection feature is supported by the USARTx instance.
1207 * @rmtoll CR2 ABRMODE LL_USART_SetAutoBaudRateMode
1208 * @param USARTx USART Instance
1209 * @param AutoBaudRateMode This parameter can be one of the following values:
1210 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1211 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1212 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1213 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1214 * @retval None
1216 __STATIC_INLINE void LL_USART_SetAutoBaudRateMode(USART_TypeDef *USARTx, uint32_t AutoBaudRateMode)
1218 MODIFY_REG(USARTx->CR2, USART_CR2_ABRMODE, AutoBaudRateMode);
1222 * @brief Return Auto Baud-Rate mode
1223 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
1224 * Auto Baud Rate detection feature is supported by the USARTx instance.
1225 * @rmtoll CR2 ABRMODE LL_USART_GetAutoBaudRateMode
1226 * @param USARTx USART Instance
1227 * @retval Returned value can be one of the following values:
1228 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_STARTBIT
1229 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_FALLINGEDGE
1230 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_7F_FRAME
1231 * @arg @ref LL_USART_AUTOBAUD_DETECT_ON_55_FRAME
1233 __STATIC_INLINE uint32_t LL_USART_GetAutoBaudRateMode(USART_TypeDef *USARTx)
1235 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ABRMODE));
1239 * @brief Enable Receiver Timeout
1240 * @rmtoll CR2 RTOEN LL_USART_EnableRxTimeout
1241 * @param USARTx USART Instance
1242 * @retval None
1244 __STATIC_INLINE void LL_USART_EnableRxTimeout(USART_TypeDef *USARTx)
1246 SET_BIT(USARTx->CR2, USART_CR2_RTOEN);
1250 * @brief Disable Receiver Timeout
1251 * @rmtoll CR2 RTOEN LL_USART_DisableRxTimeout
1252 * @param USARTx USART Instance
1253 * @retval None
1255 __STATIC_INLINE void LL_USART_DisableRxTimeout(USART_TypeDef *USARTx)
1257 CLEAR_BIT(USARTx->CR2, USART_CR2_RTOEN);
1261 * @brief Indicate if Receiver Timeout feature is enabled
1262 * @rmtoll CR2 RTOEN LL_USART_IsEnabledRxTimeout
1263 * @param USARTx USART Instance
1264 * @retval State of bit (1 or 0).
1266 __STATIC_INLINE uint32_t LL_USART_IsEnabledRxTimeout(USART_TypeDef *USARTx)
1268 return (READ_BIT(USARTx->CR2, USART_CR2_RTOEN) == (USART_CR2_RTOEN));
1272 * @brief Set Address of the USART node.
1273 * @note This is used in multiprocessor communication during Mute mode or Stop mode,
1274 * for wake up with address mark detection.
1275 * @note 4bits address node is used when 4-bit Address Detection is selected in ADDM7.
1276 * (b7-b4 should be set to 0)
1277 * 8bits address node is used when 7-bit Address Detection is selected in ADDM7.
1278 * (This is used in multiprocessor communication during Mute mode or Stop mode,
1279 * for wake up with 7-bit address mark detection.
1280 * The MSB of the character sent by the transmitter should be equal to 1.
1281 * It may also be used for character detection during normal reception,
1282 * Mute mode inactive (for example, end of block detection in ModBus protocol).
1283 * In this case, the whole received character (8-bit) is compared to the ADD[7:0]
1284 * value and CMF flag is set on match)
1285 * @rmtoll CR2 ADD LL_USART_ConfigNodeAddress\n
1286 * CR2 ADDM7 LL_USART_ConfigNodeAddress
1287 * @param USARTx USART Instance
1288 * @param AddressLen This parameter can be one of the following values:
1289 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1290 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1291 * @param NodeAddress 4 or 7 bit Address of the USART node.
1292 * @retval None
1294 __STATIC_INLINE void LL_USART_ConfigNodeAddress(USART_TypeDef *USARTx, uint32_t AddressLen, uint32_t NodeAddress)
1296 MODIFY_REG(USARTx->CR2, USART_CR2_ADD | USART_CR2_ADDM7,
1297 (uint32_t)(AddressLen | (NodeAddress << USART_CR2_ADD_Pos)));
1301 * @brief Return 8 bit Address of the USART node as set in ADD field of CR2.
1302 * @note If 4-bit Address Detection is selected in ADDM7,
1303 * only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant)
1304 * If 7-bit Address Detection is selected in ADDM7,
1305 * only 8bits (b7-b0) of returned value are relevant (b31-b8 are not relevant)
1306 * @rmtoll CR2 ADD LL_USART_GetNodeAddress
1307 * @param USARTx USART Instance
1308 * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255)
1310 __STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx)
1312 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD) >> USART_CR2_ADD_Pos);
1316 * @brief Return Length of Node Address used in Address Detection mode (7-bit or 4-bit)
1317 * @rmtoll CR2 ADDM7 LL_USART_GetNodeAddressLen
1318 * @param USARTx USART Instance
1319 * @retval Returned value can be one of the following values:
1320 * @arg @ref LL_USART_ADDRESS_DETECT_4B
1321 * @arg @ref LL_USART_ADDRESS_DETECT_7B
1323 __STATIC_INLINE uint32_t LL_USART_GetNodeAddressLen(USART_TypeDef *USARTx)
1325 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADDM7));
1329 * @brief Enable RTS HW Flow Control
1330 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1331 * Hardware Flow control feature is supported by the USARTx instance.
1332 * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl
1333 * @param USARTx USART Instance
1334 * @retval None
1336 __STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx)
1338 SET_BIT(USARTx->CR3, USART_CR3_RTSE);
1342 * @brief Disable RTS HW Flow Control
1343 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1344 * Hardware Flow control feature is supported by the USARTx instance.
1345 * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl
1346 * @param USARTx USART Instance
1347 * @retval None
1349 __STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx)
1351 CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE);
1355 * @brief Enable CTS HW Flow Control
1356 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1357 * Hardware Flow control feature is supported by the USARTx instance.
1358 * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl
1359 * @param USARTx USART Instance
1360 * @retval None
1362 __STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx)
1364 SET_BIT(USARTx->CR3, USART_CR3_CTSE);
1368 * @brief Disable CTS HW Flow Control
1369 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1370 * Hardware Flow control feature is supported by the USARTx instance.
1371 * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl
1372 * @param USARTx USART Instance
1373 * @retval None
1375 __STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx)
1377 CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE);
1381 * @brief Configure HW Flow Control mode (both CTS and RTS)
1382 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1383 * Hardware Flow control feature is supported by the USARTx instance.
1384 * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n
1385 * CR3 CTSE LL_USART_SetHWFlowCtrl
1386 * @param USARTx USART Instance
1387 * @param HardwareFlowControl This parameter can be one of the following values:
1388 * @arg @ref LL_USART_HWCONTROL_NONE
1389 * @arg @ref LL_USART_HWCONTROL_RTS
1390 * @arg @ref LL_USART_HWCONTROL_CTS
1391 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1392 * @retval None
1394 __STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl)
1396 MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl);
1400 * @brief Return HW Flow Control configuration (both CTS and RTS)
1401 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
1402 * Hardware Flow control feature is supported by the USARTx instance.
1403 * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n
1404 * CR3 CTSE LL_USART_GetHWFlowCtrl
1405 * @param USARTx USART Instance
1406 * @retval Returned value can be one of the following values:
1407 * @arg @ref LL_USART_HWCONTROL_NONE
1408 * @arg @ref LL_USART_HWCONTROL_RTS
1409 * @arg @ref LL_USART_HWCONTROL_CTS
1410 * @arg @ref LL_USART_HWCONTROL_RTS_CTS
1412 __STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx)
1414 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE));
1418 * @brief Enable One bit sampling method
1419 * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp
1420 * @param USARTx USART Instance
1421 * @retval None
1423 __STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx)
1425 SET_BIT(USARTx->CR3, USART_CR3_ONEBIT);
1429 * @brief Disable One bit sampling method
1430 * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp
1431 * @param USARTx USART Instance
1432 * @retval None
1434 __STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx)
1436 CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT);
1440 * @brief Indicate if One bit sampling method is enabled
1441 * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp
1442 * @param USARTx USART Instance
1443 * @retval State of bit (1 or 0).
1445 __STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx)
1447 return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT));
1451 * @brief Enable Overrun detection
1452 * @rmtoll CR3 OVRDIS LL_USART_EnableOverrunDetect
1453 * @param USARTx USART Instance
1454 * @retval None
1456 __STATIC_INLINE void LL_USART_EnableOverrunDetect(USART_TypeDef *USARTx)
1458 CLEAR_BIT(USARTx->CR3, USART_CR3_OVRDIS);
1462 * @brief Disable Overrun detection
1463 * @rmtoll CR3 OVRDIS LL_USART_DisableOverrunDetect
1464 * @param USARTx USART Instance
1465 * @retval None
1467 __STATIC_INLINE void LL_USART_DisableOverrunDetect(USART_TypeDef *USARTx)
1469 SET_BIT(USARTx->CR3, USART_CR3_OVRDIS);
1473 * @brief Indicate if Overrun detection is enabled
1474 * @rmtoll CR3 OVRDIS LL_USART_IsEnabledOverrunDetect
1475 * @param USARTx USART Instance
1476 * @retval State of bit (1 or 0).
1478 __STATIC_INLINE uint32_t LL_USART_IsEnabledOverrunDetect(USART_TypeDef *USARTx)
1480 return (READ_BIT(USARTx->CR3, USART_CR3_OVRDIS) != USART_CR3_OVRDIS);
1485 * @brief Configure USART BRR register for achieving expected Baud Rate value.
1486 * @note Compute and set USARTDIV value in BRR Register (full BRR content)
1487 * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values
1488 * @note Peripheral clock and Baud rate values provided as function parameters should be valid
1489 * (Baud rate value != 0)
1490 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1491 * @rmtoll BRR BRR LL_USART_SetBaudRate
1492 * @param USARTx USART Instance
1493 * @param PeriphClk Peripheral Clock
1494 * @param OverSampling This parameter can be one of the following values:
1495 * @arg @ref LL_USART_OVERSAMPLING_16
1496 * @arg @ref LL_USART_OVERSAMPLING_8
1497 * @param BaudRate Baud Rate
1498 * @retval None
1500 __STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling,
1501 uint32_t BaudRate)
1503 register uint32_t usartdiv = 0x0U;
1504 register uint32_t brrtemp = 0x0U;
1506 if (OverSampling == LL_USART_OVERSAMPLING_8)
1508 usartdiv = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate));
1509 brrtemp = usartdiv & 0xFFF0U;
1510 brrtemp |= (uint16_t)((usartdiv & (uint16_t)0x000FU) >> 1U);
1511 USARTx->BRR = brrtemp;
1513 else
1515 USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate));
1520 * @brief Return current Baud Rate value, according to USARTDIV present in BRR register
1521 * (full BRR content), and to used Peripheral Clock and Oversampling mode values
1522 * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned.
1523 * @note In case of oversampling by 16 and 8, BRR content must be greater than or equal to 16d.
1524 * @rmtoll BRR BRR LL_USART_GetBaudRate
1525 * @param USARTx USART Instance
1526 * @param PeriphClk Peripheral Clock
1527 * @param OverSampling This parameter can be one of the following values:
1528 * @arg @ref LL_USART_OVERSAMPLING_16
1529 * @arg @ref LL_USART_OVERSAMPLING_8
1530 * @retval Baud Rate
1532 __STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling)
1534 register uint32_t usartdiv = 0x0U;
1535 register uint32_t brrresult = 0x0U;
1537 usartdiv = USARTx->BRR;
1539 if (OverSampling == LL_USART_OVERSAMPLING_8)
1541 if ((usartdiv & 0xFFF7U) != 0U)
1543 usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ;
1544 brrresult = (PeriphClk * 2U) / usartdiv;
1547 else
1549 if ((usartdiv & 0xFFFFU) != 0U)
1551 brrresult = PeriphClk / usartdiv;
1554 return (brrresult);
1558 * @brief Set Receiver Time Out Value (expressed in nb of bits duration)
1559 * @rmtoll RTOR RTO LL_USART_SetRxTimeout
1560 * @param USARTx USART Instance
1561 * @param Timeout Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1562 * @retval None
1564 __STATIC_INLINE void LL_USART_SetRxTimeout(USART_TypeDef *USARTx, uint32_t Timeout)
1566 MODIFY_REG(USARTx->RTOR, USART_RTOR_RTO, Timeout);
1570 * @brief Get Receiver Time Out Value (expressed in nb of bits duration)
1571 * @rmtoll RTOR RTO LL_USART_GetRxTimeout
1572 * @param USARTx USART Instance
1573 * @retval Value between Min_Data=0x00 and Max_Data=0x00FFFFFF
1575 __STATIC_INLINE uint32_t LL_USART_GetRxTimeout(USART_TypeDef *USARTx)
1577 return (uint32_t)(READ_BIT(USARTx->RTOR, USART_RTOR_RTO));
1581 * @brief Set Block Length value in reception
1582 * @rmtoll RTOR BLEN LL_USART_SetBlockLength
1583 * @param USARTx USART Instance
1584 * @param BlockLength Value between Min_Data=0x00 and Max_Data=0xFF
1585 * @retval None
1587 __STATIC_INLINE void LL_USART_SetBlockLength(USART_TypeDef *USARTx, uint32_t BlockLength)
1589 MODIFY_REG(USARTx->RTOR, USART_RTOR_BLEN, BlockLength << USART_RTOR_BLEN_Pos);
1593 * @brief Get Block Length value in reception
1594 * @rmtoll RTOR BLEN LL_USART_GetBlockLength
1595 * @param USARTx USART Instance
1596 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
1598 __STATIC_INLINE uint32_t LL_USART_GetBlockLength(USART_TypeDef *USARTx)
1600 return (uint32_t)(READ_BIT(USARTx->RTOR, USART_RTOR_BLEN) >> USART_RTOR_BLEN_Pos);
1604 * @}
1607 /** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature
1608 * @{
1612 * @brief Enable IrDA mode
1613 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1614 * IrDA feature is supported by the USARTx instance.
1615 * @rmtoll CR3 IREN LL_USART_EnableIrda
1616 * @param USARTx USART Instance
1617 * @retval None
1619 __STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx)
1621 SET_BIT(USARTx->CR3, USART_CR3_IREN);
1625 * @brief Disable IrDA mode
1626 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1627 * IrDA feature is supported by the USARTx instance.
1628 * @rmtoll CR3 IREN LL_USART_DisableIrda
1629 * @param USARTx USART Instance
1630 * @retval None
1632 __STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx)
1634 CLEAR_BIT(USARTx->CR3, USART_CR3_IREN);
1638 * @brief Indicate if IrDA mode is enabled
1639 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1640 * IrDA feature is supported by the USARTx instance.
1641 * @rmtoll CR3 IREN LL_USART_IsEnabledIrda
1642 * @param USARTx USART Instance
1643 * @retval State of bit (1 or 0).
1645 __STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx)
1647 return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN));
1651 * @brief Configure IrDA Power Mode (Normal or Low Power)
1652 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1653 * IrDA feature is supported by the USARTx instance.
1654 * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode
1655 * @param USARTx USART Instance
1656 * @param PowerMode This parameter can be one of the following values:
1657 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1658 * @arg @ref LL_USART_IRDA_POWER_LOW
1659 * @retval None
1661 __STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode)
1663 MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode);
1667 * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power)
1668 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1669 * IrDA feature is supported by the USARTx instance.
1670 * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode
1671 * @param USARTx USART Instance
1672 * @retval Returned value can be one of the following values:
1673 * @arg @ref LL_USART_IRDA_POWER_NORMAL
1674 * @arg @ref LL_USART_PHASE_2EDGE
1676 __STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx)
1678 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP));
1682 * @brief Set Irda prescaler value, used for dividing the USART clock source
1683 * to achieve the Irda Low Power frequency (8 bits value)
1684 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
1685 * IrDA feature is supported by the USARTx instance.
1686 * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler
1687 * @param USARTx USART Instance
1688 * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF
1689 * @retval None
1691 __STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue)
1693 MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue);
1697 * @brief Return Irda prescaler value, used for dividing the USART clock source
1698 * to achieve the Irda Low Power frequency (8 bits value)
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 GTPR PSC LL_USART_GetIrdaPrescaler
1702 * @param USARTx USART Instance
1703 * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF)
1705 __STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx)
1707 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC));
1711 * @}
1714 /** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature
1715 * @{
1719 * @brief Enable Smartcard NACK transmission
1720 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1721 * Smartcard feature is supported by the USARTx instance.
1722 * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK
1723 * @param USARTx USART Instance
1724 * @retval None
1726 __STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx)
1728 SET_BIT(USARTx->CR3, USART_CR3_NACK);
1732 * @brief Disable Smartcard NACK transmission
1733 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1734 * Smartcard feature is supported by the USARTx instance.
1735 * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK
1736 * @param USARTx USART Instance
1737 * @retval None
1739 __STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx)
1741 CLEAR_BIT(USARTx->CR3, USART_CR3_NACK);
1745 * @brief Indicate if Smartcard NACK transmission is enabled
1746 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1747 * Smartcard feature is supported by the USARTx instance.
1748 * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK
1749 * @param USARTx USART Instance
1750 * @retval State of bit (1 or 0).
1752 __STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx)
1754 return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK));
1758 * @brief Enable Smartcard mode
1759 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1760 * Smartcard feature is supported by the USARTx instance.
1761 * @rmtoll CR3 SCEN LL_USART_EnableSmartcard
1762 * @param USARTx USART Instance
1763 * @retval None
1765 __STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx)
1767 SET_BIT(USARTx->CR3, USART_CR3_SCEN);
1771 * @brief Disable Smartcard mode
1772 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1773 * Smartcard feature is supported by the USARTx instance.
1774 * @rmtoll CR3 SCEN LL_USART_DisableSmartcard
1775 * @param USARTx USART Instance
1776 * @retval None
1778 __STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx)
1780 CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN);
1784 * @brief Indicate if Smartcard mode is enabled
1785 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1786 * Smartcard feature is supported by the USARTx instance.
1787 * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard
1788 * @param USARTx USART Instance
1789 * @retval State of bit (1 or 0).
1791 __STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx)
1793 return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN));
1797 * @brief Set Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1798 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1799 * Smartcard feature is supported by the USARTx instance.
1800 * @note This bit-field specifies the number of retries in transmit and receive, in Smartcard mode.
1801 * In transmission mode, it specifies the number of automatic retransmission retries, before
1802 * generating a transmission error (FE bit set).
1803 * In reception mode, it specifies the number or erroneous reception trials, before generating a
1804 * reception error (RXNE and PE bits set)
1805 * @rmtoll CR3 SCARCNT LL_USART_SetSmartcardAutoRetryCount
1806 * @param USARTx USART Instance
1807 * @param AutoRetryCount Value between Min_Data=0 and Max_Data=7
1808 * @retval None
1810 __STATIC_INLINE void LL_USART_SetSmartcardAutoRetryCount(USART_TypeDef *USARTx, uint32_t AutoRetryCount)
1812 MODIFY_REG(USARTx->CR3, USART_CR3_SCARCNT, AutoRetryCount << USART_CR3_SCARCNT_Pos);
1816 * @brief Return Smartcard Auto-Retry Count value (SCARCNT[2:0] bits)
1817 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1818 * Smartcard feature is supported by the USARTx instance.
1819 * @rmtoll CR3 SCARCNT LL_USART_GetSmartcardAutoRetryCount
1820 * @param USARTx USART Instance
1821 * @retval Smartcard Auto-Retry Count value (Value between Min_Data=0 and Max_Data=7)
1823 __STATIC_INLINE uint32_t LL_USART_GetSmartcardAutoRetryCount(USART_TypeDef *USARTx)
1825 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_SCARCNT) >> USART_CR3_SCARCNT_Pos);
1829 * @brief Set Smartcard prescaler value, used for dividing the USART clock
1830 * source to provide the SMARTCARD Clock (5 bits value)
1831 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1832 * Smartcard feature is supported by the USARTx instance.
1833 * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler
1834 * @param USARTx USART Instance
1835 * @param PrescalerValue Value between Min_Data=0 and Max_Data=31
1836 * @retval None
1838 __STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue)
1840 MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue);
1844 * @brief Return Smartcard prescaler value, used for dividing the USART clock
1845 * source to provide the SMARTCARD Clock (5 bits value)
1846 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1847 * Smartcard feature is supported by the USARTx instance.
1848 * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler
1849 * @param USARTx USART Instance
1850 * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31)
1852 __STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx)
1854 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC));
1858 * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods
1859 * (GT[7:0] bits : Guard time value)
1860 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1861 * Smartcard feature is supported by the USARTx instance.
1862 * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime
1863 * @param USARTx USART Instance
1864 * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF
1865 * @retval None
1867 __STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime)
1869 MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_GTPR_GT_Pos);
1873 * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods
1874 * (GT[7:0] bits : Guard time value)
1875 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
1876 * Smartcard feature is supported by the USARTx instance.
1877 * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime
1878 * @param USARTx USART Instance
1879 * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF)
1881 __STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx)
1883 return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_GTPR_GT_Pos);
1887 * @}
1890 /** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature
1891 * @{
1895 * @brief Enable Single Wire Half-Duplex mode
1896 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1897 * Half-Duplex mode is supported by the USARTx instance.
1898 * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex
1899 * @param USARTx USART Instance
1900 * @retval None
1902 __STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx)
1904 SET_BIT(USARTx->CR3, USART_CR3_HDSEL);
1908 * @brief Disable Single Wire Half-Duplex mode
1909 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1910 * Half-Duplex mode is supported by the USARTx instance.
1911 * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex
1912 * @param USARTx USART Instance
1913 * @retval None
1915 __STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx)
1917 CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL);
1921 * @brief Indicate if Single Wire Half-Duplex mode is enabled
1922 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
1923 * Half-Duplex mode is supported by the USARTx instance.
1924 * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex
1925 * @param USARTx USART Instance
1926 * @retval State of bit (1 or 0).
1928 __STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx)
1930 return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL));
1934 * @}
1937 /** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature
1938 * @{
1942 * @brief Set LIN Break Detection Length
1943 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1944 * LIN feature is supported by the USARTx instance.
1945 * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen
1946 * @param USARTx USART Instance
1947 * @param LINBDLength This parameter can be one of the following values:
1948 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1949 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1950 * @retval None
1952 __STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength)
1954 MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength);
1958 * @brief Return LIN Break Detection Length
1959 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1960 * LIN feature is supported by the USARTx instance.
1961 * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen
1962 * @param USARTx USART Instance
1963 * @retval Returned value can be one of the following values:
1964 * @arg @ref LL_USART_LINBREAK_DETECT_10B
1965 * @arg @ref LL_USART_LINBREAK_DETECT_11B
1967 __STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx)
1969 return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL));
1973 * @brief Enable LIN mode
1974 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1975 * LIN feature is supported by the USARTx instance.
1976 * @rmtoll CR2 LINEN LL_USART_EnableLIN
1977 * @param USARTx USART Instance
1978 * @retval None
1980 __STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx)
1982 SET_BIT(USARTx->CR2, USART_CR2_LINEN);
1986 * @brief Disable LIN mode
1987 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
1988 * LIN feature is supported by the USARTx instance.
1989 * @rmtoll CR2 LINEN LL_USART_DisableLIN
1990 * @param USARTx USART Instance
1991 * @retval None
1993 __STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx)
1995 CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN);
1999 * @brief Indicate if LIN mode is enabled
2000 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2001 * LIN feature is supported by the USARTx instance.
2002 * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN
2003 * @param USARTx USART Instance
2004 * @retval State of bit (1 or 0).
2006 __STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx)
2008 return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN));
2012 * @}
2015 /** @defgroup USART_LL_EF_Configuration_DE Configuration functions related to Driver Enable feature
2016 * @{
2020 * @brief Set DEDT (Driver Enable De-Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2021 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2022 * Driver Enable feature is supported by the USARTx instance.
2023 * @rmtoll CR1 DEDT LL_USART_SetDEDeassertionTime
2024 * @param USARTx USART Instance
2025 * @param Time Value between Min_Data=0 and Max_Data=31
2026 * @retval None
2028 __STATIC_INLINE void LL_USART_SetDEDeassertionTime(USART_TypeDef *USARTx, uint32_t Time)
2030 MODIFY_REG(USARTx->CR1, USART_CR1_DEDT, Time << USART_CR1_DEDT_Pos);
2034 * @brief Return DEDT (Driver Enable De-Assertion Time)
2035 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2036 * Driver Enable feature is supported by the USARTx instance.
2037 * @rmtoll CR1 DEDT LL_USART_GetDEDeassertionTime
2038 * @param USARTx USART Instance
2039 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2041 __STATIC_INLINE uint32_t LL_USART_GetDEDeassertionTime(USART_TypeDef *USARTx)
2043 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_DEDT) >> USART_CR1_DEDT_Pos);
2047 * @brief Set DEAT (Driver Enable Assertion Time), Time value expressed on 5 bits ([4:0] bits).
2048 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2049 * Driver Enable feature is supported by the USARTx instance.
2050 * @rmtoll CR1 DEAT LL_USART_SetDEAssertionTime
2051 * @param USARTx USART Instance
2052 * @param Time Value between Min_Data=0 and Max_Data=31
2053 * @retval None
2055 __STATIC_INLINE void LL_USART_SetDEAssertionTime(USART_TypeDef *USARTx, uint32_t Time)
2057 MODIFY_REG(USARTx->CR1, USART_CR1_DEAT, Time << USART_CR1_DEAT_Pos);
2061 * @brief Return DEAT (Driver Enable Assertion Time)
2062 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2063 * Driver Enable feature is supported by the USARTx instance.
2064 * @rmtoll CR1 DEAT LL_USART_GetDEAssertionTime
2065 * @param USARTx USART Instance
2066 * @retval Time value expressed on 5 bits ([4:0] bits) : Value between Min_Data=0 and Max_Data=31
2068 __STATIC_INLINE uint32_t LL_USART_GetDEAssertionTime(USART_TypeDef *USARTx)
2070 return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_DEAT) >> USART_CR1_DEAT_Pos);
2074 * @brief Enable Driver Enable (DE) Mode
2075 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2076 * Driver Enable feature is supported by the USARTx instance.
2077 * @rmtoll CR3 DEM LL_USART_EnableDEMode
2078 * @param USARTx USART Instance
2079 * @retval None
2081 __STATIC_INLINE void LL_USART_EnableDEMode(USART_TypeDef *USARTx)
2083 SET_BIT(USARTx->CR3, USART_CR3_DEM);
2087 * @brief Disable Driver Enable (DE) Mode
2088 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2089 * Driver Enable feature is supported by the USARTx instance.
2090 * @rmtoll CR3 DEM LL_USART_DisableDEMode
2091 * @param USARTx USART Instance
2092 * @retval None
2094 __STATIC_INLINE void LL_USART_DisableDEMode(USART_TypeDef *USARTx)
2096 CLEAR_BIT(USARTx->CR3, USART_CR3_DEM);
2100 * @brief Indicate if Driver Enable (DE) Mode is enabled
2101 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2102 * Driver Enable feature is supported by the USARTx instance.
2103 * @rmtoll CR3 DEM LL_USART_IsEnabledDEMode
2104 * @param USARTx USART Instance
2105 * @retval State of bit (1 or 0).
2107 __STATIC_INLINE uint32_t LL_USART_IsEnabledDEMode(USART_TypeDef *USARTx)
2109 return (READ_BIT(USARTx->CR3, USART_CR3_DEM) == (USART_CR3_DEM));
2113 * @brief Select Driver Enable Polarity
2114 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2115 * Driver Enable feature is supported by the USARTx instance.
2116 * @rmtoll CR3 DEP LL_USART_SetDESignalPolarity
2117 * @param USARTx USART Instance
2118 * @param Polarity This parameter can be one of the following values:
2119 * @arg @ref LL_USART_DE_POLARITY_HIGH
2120 * @arg @ref LL_USART_DE_POLARITY_LOW
2121 * @retval None
2123 __STATIC_INLINE void LL_USART_SetDESignalPolarity(USART_TypeDef *USARTx, uint32_t Polarity)
2125 MODIFY_REG(USARTx->CR3, USART_CR3_DEP, Polarity);
2129 * @brief Return Driver Enable Polarity
2130 * @note Macro @ref IS_UART_DRIVER_ENABLE_INSTANCE(USARTx) can be used to check whether or not
2131 * Driver Enable feature is supported by the USARTx instance.
2132 * @rmtoll CR3 DEP LL_USART_GetDESignalPolarity
2133 * @param USARTx USART Instance
2134 * @retval Returned value can be one of the following values:
2135 * @arg @ref LL_USART_DE_POLARITY_HIGH
2136 * @arg @ref LL_USART_DE_POLARITY_LOW
2138 __STATIC_INLINE uint32_t LL_USART_GetDESignalPolarity(USART_TypeDef *USARTx)
2140 return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_DEP));
2144 * @}
2147 /** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services
2148 * @{
2152 * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART)
2153 * @note In UART mode, the following bits must be kept cleared:
2154 * - LINEN bit in the USART_CR2 register,
2155 * - CLKEN bit in the USART_CR2 register,
2156 * - SCEN bit in the USART_CR3 register,
2157 * - IREN bit in the USART_CR3 register,
2158 * - HDSEL bit in the USART_CR3 register.
2159 * @note Call of this function is equivalent to following function call sequence :
2160 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2161 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2162 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2163 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2164 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2165 * @note Other remaining configurations items related to Asynchronous Mode
2166 * (as Baud Rate, Word length, Parity, ...) should be set using
2167 * dedicated functions
2168 * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n
2169 * CR2 CLKEN LL_USART_ConfigAsyncMode\n
2170 * CR3 SCEN LL_USART_ConfigAsyncMode\n
2171 * CR3 IREN LL_USART_ConfigAsyncMode\n
2172 * CR3 HDSEL LL_USART_ConfigAsyncMode
2173 * @param USARTx USART Instance
2174 * @retval None
2176 __STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx)
2178 /* In Asynchronous mode, the following bits must be kept cleared:
2179 - LINEN, CLKEN bits in the USART_CR2 register,
2180 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2181 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2182 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL));
2186 * @brief Perform basic configuration of USART for enabling use in Synchronous Mode
2187 * @note In Synchronous mode, the following bits must be kept cleared:
2188 * - LINEN bit in the USART_CR2 register,
2189 * - SCEN bit in the USART_CR3 register,
2190 * - IREN bit in the USART_CR3 register,
2191 * - HDSEL bit in the USART_CR3 register.
2192 * This function also sets the USART in Synchronous mode.
2193 * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not
2194 * Synchronous mode is supported by the USARTx instance.
2195 * @note Call of this function is equivalent to following function call sequence :
2196 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2197 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2198 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2199 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2200 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2201 * @note Other remaining configurations items related to Synchronous Mode
2202 * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using
2203 * dedicated functions
2204 * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n
2205 * CR2 CLKEN LL_USART_ConfigSyncMode\n
2206 * CR3 SCEN LL_USART_ConfigSyncMode\n
2207 * CR3 IREN LL_USART_ConfigSyncMode\n
2208 * CR3 HDSEL LL_USART_ConfigSyncMode
2209 * @param USARTx USART Instance
2210 * @retval None
2212 __STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx)
2214 /* In Synchronous mode, the following bits must be kept cleared:
2215 - LINEN bit in the USART_CR2 register,
2216 - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/
2217 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN));
2218 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL));
2219 /* set the UART/USART in Synchronous mode */
2220 SET_BIT(USARTx->CR2, USART_CR2_CLKEN);
2224 * @brief Perform basic configuration of USART for enabling use in LIN Mode
2225 * @note In LIN mode, the following bits must be kept cleared:
2226 * - STOP and CLKEN bits in the USART_CR2 register,
2227 * - SCEN bit in the USART_CR3 register,
2228 * - IREN bit in the USART_CR3 register,
2229 * - HDSEL bit in the USART_CR3 register.
2230 * This function also set the UART/USART in LIN mode.
2231 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2232 * LIN feature is supported by the USARTx instance.
2233 * @note Call of this function is equivalent to following function call sequence :
2234 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2235 * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2236 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2237 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2238 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2239 * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function
2240 * @note Other remaining configurations items related to LIN Mode
2241 * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using
2242 * dedicated functions
2243 * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n
2244 * CR2 STOP LL_USART_ConfigLINMode\n
2245 * CR2 LINEN LL_USART_ConfigLINMode\n
2246 * CR3 IREN LL_USART_ConfigLINMode\n
2247 * CR3 SCEN LL_USART_ConfigLINMode\n
2248 * CR3 HDSEL LL_USART_ConfigLINMode
2249 * @param USARTx USART Instance
2250 * @retval None
2252 __STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx)
2254 /* In LIN mode, the following bits must be kept cleared:
2255 - STOP and CLKEN bits in the USART_CR2 register,
2256 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2257 CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP));
2258 CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL));
2259 /* Set the UART/USART in LIN mode */
2260 SET_BIT(USARTx->CR2, USART_CR2_LINEN);
2264 * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode
2265 * @note In Half Duplex mode, the following bits must be kept cleared:
2266 * - LINEN bit in the USART_CR2 register,
2267 * - CLKEN bit in the USART_CR2 register,
2268 * - SCEN bit in the USART_CR3 register,
2269 * - IREN bit in the USART_CR3 register,
2270 * This function also sets the UART/USART in Half Duplex mode.
2271 * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not
2272 * Half-Duplex mode is supported by the USARTx instance.
2273 * @note Call of this function is equivalent to following function call sequence :
2274 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2275 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2276 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2277 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2278 * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function
2279 * @note Other remaining configurations items related to Half Duplex Mode
2280 * (as Baud Rate, Word length, Parity, ...) should be set using
2281 * dedicated functions
2282 * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n
2283 * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n
2284 * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n
2285 * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n
2286 * CR3 IREN LL_USART_ConfigHalfDuplexMode
2287 * @param USARTx USART Instance
2288 * @retval None
2290 __STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx)
2292 /* In Half Duplex mode, the following bits must be kept cleared:
2293 - LINEN and CLKEN bits in the USART_CR2 register,
2294 - SCEN and IREN bits in the USART_CR3 register.*/
2295 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2296 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN));
2297 /* set the UART/USART in Half Duplex mode */
2298 SET_BIT(USARTx->CR3, USART_CR3_HDSEL);
2302 * @brief Perform basic configuration of USART for enabling use in Smartcard Mode
2303 * @note In Smartcard mode, the following bits must be kept cleared:
2304 * - LINEN bit in the USART_CR2 register,
2305 * - IREN bit in the USART_CR3 register,
2306 * - HDSEL bit in the USART_CR3 register.
2307 * This function also configures Stop bits to 1.5 bits and
2308 * sets the USART in Smartcard mode (SCEN bit).
2309 * Clock Output is also enabled (CLKEN).
2310 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2311 * Smartcard feature is supported by the USARTx instance.
2312 * @note Call of this function is equivalent to following function call sequence :
2313 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2314 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2315 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2316 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2317 * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function
2318 * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function
2319 * @note Other remaining configurations items related to Smartcard Mode
2320 * (as Baud Rate, Word length, Parity, ...) should be set using
2321 * dedicated functions
2322 * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n
2323 * CR2 STOP LL_USART_ConfigSmartcardMode\n
2324 * CR2 CLKEN LL_USART_ConfigSmartcardMode\n
2325 * CR3 HDSEL LL_USART_ConfigSmartcardMode\n
2326 * CR3 SCEN LL_USART_ConfigSmartcardMode
2327 * @param USARTx USART Instance
2328 * @retval None
2330 __STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx)
2332 /* In Smartcard mode, the following bits must be kept cleared:
2333 - LINEN bit in the USART_CR2 register,
2334 - IREN and HDSEL bits in the USART_CR3 register.*/
2335 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN));
2336 CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL));
2337 /* Configure Stop bits to 1.5 bits */
2338 /* Synchronous mode is activated by default */
2339 SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN));
2340 /* set the UART/USART in Smartcard mode */
2341 SET_BIT(USARTx->CR3, USART_CR3_SCEN);
2345 * @brief Perform basic configuration of USART for enabling use in Irda Mode
2346 * @note In IRDA mode, the following bits must be kept cleared:
2347 * - LINEN bit in the USART_CR2 register,
2348 * - STOP and CLKEN bits in the USART_CR2 register,
2349 * - SCEN bit in the USART_CR3 register,
2350 * - HDSEL bit in the USART_CR3 register.
2351 * This function also sets the UART/USART in IRDA mode (IREN bit).
2352 * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not
2353 * IrDA feature is supported by the USARTx instance.
2354 * @note Call of this function is equivalent to following function call sequence :
2355 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2356 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2357 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2358 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2359 * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function
2360 * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function
2361 * @note Other remaining configurations items related to Irda Mode
2362 * (as Baud Rate, Word length, Power mode, ...) should be set using
2363 * dedicated functions
2364 * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n
2365 * CR2 CLKEN LL_USART_ConfigIrdaMode\n
2366 * CR2 STOP LL_USART_ConfigIrdaMode\n
2367 * CR3 SCEN LL_USART_ConfigIrdaMode\n
2368 * CR3 HDSEL LL_USART_ConfigIrdaMode\n
2369 * CR3 IREN LL_USART_ConfigIrdaMode
2370 * @param USARTx USART Instance
2371 * @retval None
2373 __STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx)
2375 /* In IRDA mode, the following bits must be kept cleared:
2376 - LINEN, STOP and CLKEN bits in the USART_CR2 register,
2377 - SCEN and HDSEL bits in the USART_CR3 register.*/
2378 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP));
2379 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL));
2380 /* set the UART/USART in IRDA mode */
2381 SET_BIT(USARTx->CR3, USART_CR3_IREN);
2385 * @brief Perform basic configuration of USART for enabling use in Multi processor Mode
2386 * (several USARTs connected in a network, one of the USARTs can be the master,
2387 * its TX output connected to the RX inputs of the other slaves USARTs).
2388 * @note In MultiProcessor mode, the following bits must be kept cleared:
2389 * - LINEN bit in the USART_CR2 register,
2390 * - CLKEN bit in the USART_CR2 register,
2391 * - SCEN bit in the USART_CR3 register,
2392 * - IREN bit in the USART_CR3 register,
2393 * - HDSEL bit in the USART_CR3 register.
2394 * @note Call of this function is equivalent to following function call sequence :
2395 * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function
2396 * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function
2397 * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function
2398 * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function
2399 * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function
2400 * @note Other remaining configurations items related to Multi processor Mode
2401 * (as Baud Rate, Wake Up Method, Node address, ...) should be set using
2402 * dedicated functions
2403 * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n
2404 * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n
2405 * CR3 SCEN LL_USART_ConfigMultiProcessMode\n
2406 * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n
2407 * CR3 IREN LL_USART_ConfigMultiProcessMode
2408 * @param USARTx USART Instance
2409 * @retval None
2411 __STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx)
2413 /* In Multi Processor mode, the following bits must be kept cleared:
2414 - LINEN and CLKEN bits in the USART_CR2 register,
2415 - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/
2416 CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN));
2417 CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN));
2421 * @}
2424 /** @defgroup USART_LL_EF_FLAG_Management FLAG_Management
2425 * @{
2429 * @brief Check if the USART Parity Error Flag is set or not
2430 * @rmtoll ISR PE LL_USART_IsActiveFlag_PE
2431 * @param USARTx USART Instance
2432 * @retval State of bit (1 or 0).
2434 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx)
2436 return (READ_BIT(USARTx->ISR, USART_ISR_PE) == (USART_ISR_PE));
2440 * @brief Check if the USART Framing Error Flag is set or not
2441 * @rmtoll ISR FE LL_USART_IsActiveFlag_FE
2442 * @param USARTx USART Instance
2443 * @retval State of bit (1 or 0).
2445 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx)
2447 return (READ_BIT(USARTx->ISR, USART_ISR_FE) == (USART_ISR_FE));
2451 * @brief Check if the USART Noise error detected Flag is set or not
2452 * @rmtoll ISR NF LL_USART_IsActiveFlag_NE
2453 * @param USARTx USART Instance
2454 * @retval State of bit (1 or 0).
2456 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx)
2458 return (READ_BIT(USARTx->ISR, USART_ISR_NE) == (USART_ISR_NE));
2462 * @brief Check if the USART OverRun Error Flag is set or not
2463 * @rmtoll ISR ORE LL_USART_IsActiveFlag_ORE
2464 * @param USARTx USART Instance
2465 * @retval State of bit (1 or 0).
2467 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx)
2469 return (READ_BIT(USARTx->ISR, USART_ISR_ORE) == (USART_ISR_ORE));
2473 * @brief Check if the USART IDLE line detected Flag is set or not
2474 * @rmtoll ISR IDLE LL_USART_IsActiveFlag_IDLE
2475 * @param USARTx USART Instance
2476 * @retval State of bit (1 or 0).
2478 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx)
2480 return (READ_BIT(USARTx->ISR, USART_ISR_IDLE) == (USART_ISR_IDLE));
2484 * @brief Check if the USART Read Data Register Not Empty Flag is set or not
2485 * @rmtoll ISR RXNE LL_USART_IsActiveFlag_RXNE
2486 * @param USARTx USART Instance
2487 * @retval State of bit (1 or 0).
2489 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx)
2491 return (READ_BIT(USARTx->ISR, USART_ISR_RXNE) == (USART_ISR_RXNE));
2495 * @brief Check if the USART Transmission Complete Flag is set or not
2496 * @rmtoll ISR TC LL_USART_IsActiveFlag_TC
2497 * @param USARTx USART Instance
2498 * @retval State of bit (1 or 0).
2500 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx)
2502 return (READ_BIT(USARTx->ISR, USART_ISR_TC) == (USART_ISR_TC));
2506 * @brief Check if the USART Transmit Data Register Empty Flag is set or not
2507 * @rmtoll ISR TXE LL_USART_IsActiveFlag_TXE
2508 * @param USARTx USART Instance
2509 * @retval State of bit (1 or 0).
2511 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx)
2513 return (READ_BIT(USARTx->ISR, USART_ISR_TXE) == (USART_ISR_TXE));
2517 * @brief Check if the USART LIN Break Detection Flag is set or not
2518 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2519 * LIN feature is supported by the USARTx instance.
2520 * @rmtoll ISR LBDF LL_USART_IsActiveFlag_LBD
2521 * @param USARTx USART Instance
2522 * @retval State of bit (1 or 0).
2524 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx)
2526 return (READ_BIT(USARTx->ISR, USART_ISR_LBDF) == (USART_ISR_LBDF));
2530 * @brief Check if the USART CTS interrupt Flag is set or not
2531 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2532 * Hardware Flow control feature is supported by the USARTx instance.
2533 * @rmtoll ISR CTSIF LL_USART_IsActiveFlag_nCTS
2534 * @param USARTx USART Instance
2535 * @retval State of bit (1 or 0).
2537 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx)
2539 return (READ_BIT(USARTx->ISR, USART_ISR_CTSIF) == (USART_ISR_CTSIF));
2543 * @brief Check if the USART CTS Flag is set or not
2544 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2545 * Hardware Flow control feature is supported by the USARTx instance.
2546 * @rmtoll ISR CTS LL_USART_IsActiveFlag_CTS
2547 * @param USARTx USART Instance
2548 * @retval State of bit (1 or 0).
2550 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_CTS(USART_TypeDef *USARTx)
2552 return (READ_BIT(USARTx->ISR, USART_ISR_CTS) == (USART_ISR_CTS));
2556 * @brief Check if the USART Receiver Time Out Flag is set or not
2557 * @rmtoll ISR RTOF LL_USART_IsActiveFlag_RTO
2558 * @param USARTx USART Instance
2559 * @retval State of bit (1 or 0).
2561 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RTO(USART_TypeDef *USARTx)
2563 return (READ_BIT(USARTx->ISR, USART_ISR_RTOF) == (USART_ISR_RTOF));
2567 * @brief Check if the USART End Of Block Flag is set or not
2568 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2569 * Smartcard feature is supported by the USARTx instance.
2570 * @rmtoll ISR EOBF LL_USART_IsActiveFlag_EOB
2571 * @param USARTx USART Instance
2572 * @retval State of bit (1 or 0).
2574 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_EOB(USART_TypeDef *USARTx)
2576 return (READ_BIT(USARTx->ISR, USART_ISR_EOBF) == (USART_ISR_EOBF));
2580 * @brief Check if the USART Auto-Baud Rate Error Flag is set or not
2581 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2582 * Auto Baud Rate detection feature is supported by the USARTx instance.
2583 * @rmtoll ISR ABRE LL_USART_IsActiveFlag_ABRE
2584 * @param USARTx USART Instance
2585 * @retval State of bit (1 or 0).
2587 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ABRE(USART_TypeDef *USARTx)
2589 return (READ_BIT(USARTx->ISR, USART_ISR_ABRE) == (USART_ISR_ABRE));
2593 * @brief Check if the USART Auto-Baud Rate Flag is set or not
2594 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
2595 * Auto Baud Rate detection feature is supported by the USARTx instance.
2596 * @rmtoll ISR ABRF LL_USART_IsActiveFlag_ABR
2597 * @param USARTx USART Instance
2598 * @retval State of bit (1 or 0).
2600 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ABR(USART_TypeDef *USARTx)
2602 return (READ_BIT(USARTx->ISR, USART_ISR_ABRF) == (USART_ISR_ABRF));
2606 * @brief Check if the USART Busy Flag is set or not
2607 * @rmtoll ISR BUSY LL_USART_IsActiveFlag_BUSY
2608 * @param USARTx USART Instance
2609 * @retval State of bit (1 or 0).
2611 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_BUSY(USART_TypeDef *USARTx)
2613 return (READ_BIT(USARTx->ISR, USART_ISR_BUSY) == (USART_ISR_BUSY));
2617 * @brief Check if the USART Character Match Flag is set or not
2618 * @rmtoll ISR CMF LL_USART_IsActiveFlag_CM
2619 * @param USARTx USART Instance
2620 * @retval State of bit (1 or 0).
2622 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_CM(USART_TypeDef *USARTx)
2624 return (READ_BIT(USARTx->ISR, USART_ISR_CMF) == (USART_ISR_CMF));
2628 * @brief Check if the USART Send Break Flag is set or not
2629 * @rmtoll ISR SBKF LL_USART_IsActiveFlag_SBK
2630 * @param USARTx USART Instance
2631 * @retval State of bit (1 or 0).
2633 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx)
2635 return (READ_BIT(USARTx->ISR, USART_ISR_SBKF) == (USART_ISR_SBKF));
2639 * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not
2640 * @rmtoll ISR RWU LL_USART_IsActiveFlag_RWU
2641 * @param USARTx USART Instance
2642 * @retval State of bit (1 or 0).
2644 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx)
2646 return (READ_BIT(USARTx->ISR, USART_ISR_RWU) == (USART_ISR_RWU));
2651 * @brief Check if the USART Transmit Enable Acknowledge Flag is set or not
2652 * @rmtoll ISR TEACK LL_USART_IsActiveFlag_TEACK
2653 * @param USARTx USART Instance
2654 * @retval State of bit (1 or 0).
2656 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TEACK(USART_TypeDef *USARTx)
2658 return (READ_BIT(USARTx->ISR, USART_ISR_TEACK) == (USART_ISR_TEACK));
2662 #if defined(USART_TCBGT_SUPPORT)
2663 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2665 * @brief Check if the Smartcard Transmission Complete Before Guard Time Flag is set or not
2666 * @rmtoll ISR TCBGT LL_USART_IsActiveFlag_TCBGT
2667 * @param USARTx USART Instance
2668 * @retval State of bit (1 or 0).
2670 __STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TCBGT(USART_TypeDef *USARTx)
2672 return (READ_BIT(USARTx->ISR, USART_ISR_TCBGT) == (USART_ISR_TCBGT));
2674 #endif
2677 * @brief Clear Parity Error Flag
2678 * @rmtoll ICR PECF LL_USART_ClearFlag_PE
2679 * @param USARTx USART Instance
2680 * @retval None
2682 __STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx)
2684 WRITE_REG(USARTx->ICR, USART_ICR_PECF);
2688 * @brief Clear Framing Error Flag
2689 * @rmtoll ICR FECF LL_USART_ClearFlag_FE
2690 * @param USARTx USART Instance
2691 * @retval None
2693 __STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx)
2695 WRITE_REG(USARTx->ICR, USART_ICR_FECF);
2699 * @brief Clear Noise detected Flag
2700 * @rmtoll ICR NCF LL_USART_ClearFlag_NE
2701 * @param USARTx USART Instance
2702 * @retval None
2704 __STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx)
2706 WRITE_REG(USARTx->ICR, USART_ICR_NCF);
2710 * @brief Clear OverRun Error Flag
2711 * @rmtoll ICR ORECF LL_USART_ClearFlag_ORE
2712 * @param USARTx USART Instance
2713 * @retval None
2715 __STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx)
2717 WRITE_REG(USARTx->ICR, USART_ICR_ORECF);
2721 * @brief Clear IDLE line detected Flag
2722 * @rmtoll ICR IDLECF LL_USART_ClearFlag_IDLE
2723 * @param USARTx USART Instance
2724 * @retval None
2726 __STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx)
2728 WRITE_REG(USARTx->ICR, USART_ICR_IDLECF);
2732 * @brief Clear Transmission Complete Flag
2733 * @rmtoll ICR TCCF LL_USART_ClearFlag_TC
2734 * @param USARTx USART Instance
2735 * @retval None
2737 __STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx)
2739 WRITE_REG(USARTx->ICR, USART_ICR_TCCF);
2742 #if defined(USART_TCBGT_SUPPORT)
2743 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2745 * @brief Clear Smartcard Transmission Complete Before Guard Time Flag
2746 * @rmtoll ICR TCBGTCF LL_USART_ClearFlag_TCBGT
2747 * @param USARTx USART Instance
2748 * @retval None
2750 __STATIC_INLINE void LL_USART_ClearFlag_TCBGT(USART_TypeDef *USARTx)
2752 WRITE_REG(USARTx->ICR, USART_ICR_TCBGTCF);
2754 #endif
2757 * @brief Clear LIN Break Detection Flag
2758 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2759 * LIN feature is supported by the USARTx instance.
2760 * @rmtoll ICR LBDCF LL_USART_ClearFlag_LBD
2761 * @param USARTx USART Instance
2762 * @retval None
2764 __STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx)
2766 WRITE_REG(USARTx->ICR, USART_ICR_LBDCF);
2770 * @brief Clear CTS Interrupt Flag
2771 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2772 * Hardware Flow control feature is supported by the USARTx instance.
2773 * @rmtoll ICR CTSCF LL_USART_ClearFlag_nCTS
2774 * @param USARTx USART Instance
2775 * @retval None
2777 __STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx)
2779 WRITE_REG(USARTx->ICR, USART_ICR_CTSCF);
2783 * @brief Clear Receiver Time Out Flag
2784 * @rmtoll ICR RTOCF LL_USART_ClearFlag_RTO
2785 * @param USARTx USART Instance
2786 * @retval None
2788 __STATIC_INLINE void LL_USART_ClearFlag_RTO(USART_TypeDef *USARTx)
2790 WRITE_REG(USARTx->ICR, USART_ICR_RTOCF);
2794 * @brief Clear End Of Block Flag
2795 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2796 * Smartcard feature is supported by the USARTx instance.
2797 * @rmtoll ICR EOBCF LL_USART_ClearFlag_EOB
2798 * @param USARTx USART Instance
2799 * @retval None
2801 __STATIC_INLINE void LL_USART_ClearFlag_EOB(USART_TypeDef *USARTx)
2803 WRITE_REG(USARTx->ICR, USART_ICR_EOBCF);
2807 * @brief Clear Character Match Flag
2808 * @rmtoll ICR CMCF LL_USART_ClearFlag_CM
2809 * @param USARTx USART Instance
2810 * @retval None
2812 __STATIC_INLINE void LL_USART_ClearFlag_CM(USART_TypeDef *USARTx)
2814 WRITE_REG(USARTx->ICR, USART_ICR_CMCF);
2819 * @}
2822 /** @defgroup USART_LL_EF_IT_Management IT_Management
2823 * @{
2827 * @brief Enable IDLE Interrupt
2828 * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE
2829 * @param USARTx USART Instance
2830 * @retval None
2832 __STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx)
2834 SET_BIT(USARTx->CR1, USART_CR1_IDLEIE);
2838 * @brief Enable RX Not Empty Interrupt
2839 * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE
2840 * @param USARTx USART Instance
2841 * @retval None
2843 __STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx)
2845 SET_BIT(USARTx->CR1, USART_CR1_RXNEIE);
2849 * @brief Enable Transmission Complete Interrupt
2850 * @rmtoll CR1 TCIE LL_USART_EnableIT_TC
2851 * @param USARTx USART Instance
2852 * @retval None
2854 __STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx)
2856 SET_BIT(USARTx->CR1, USART_CR1_TCIE);
2860 * @brief Enable TX Empty Interrupt
2861 * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE
2862 * @param USARTx USART Instance
2863 * @retval None
2865 __STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx)
2867 SET_BIT(USARTx->CR1, USART_CR1_TXEIE);
2871 * @brief Enable Parity Error Interrupt
2872 * @rmtoll CR1 PEIE LL_USART_EnableIT_PE
2873 * @param USARTx USART Instance
2874 * @retval None
2876 __STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx)
2878 SET_BIT(USARTx->CR1, USART_CR1_PEIE);
2882 * @brief Enable Character Match Interrupt
2883 * @rmtoll CR1 CMIE LL_USART_EnableIT_CM
2884 * @param USARTx USART Instance
2885 * @retval None
2887 __STATIC_INLINE void LL_USART_EnableIT_CM(USART_TypeDef *USARTx)
2889 SET_BIT(USARTx->CR1, USART_CR1_CMIE);
2893 * @brief Enable Receiver Timeout Interrupt
2894 * @rmtoll CR1 RTOIE LL_USART_EnableIT_RTO
2895 * @param USARTx USART Instance
2896 * @retval None
2898 __STATIC_INLINE void LL_USART_EnableIT_RTO(USART_TypeDef *USARTx)
2900 SET_BIT(USARTx->CR1, USART_CR1_RTOIE);
2904 * @brief Enable End Of Block Interrupt
2905 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2906 * Smartcard feature is supported by the USARTx instance.
2907 * @rmtoll CR1 EOBIE LL_USART_EnableIT_EOB
2908 * @param USARTx USART Instance
2909 * @retval None
2911 __STATIC_INLINE void LL_USART_EnableIT_EOB(USART_TypeDef *USARTx)
2913 SET_BIT(USARTx->CR1, USART_CR1_EOBIE);
2917 * @brief Enable LIN Break Detection Interrupt
2918 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
2919 * LIN feature is supported by the USARTx instance.
2920 * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD
2921 * @param USARTx USART Instance
2922 * @retval None
2924 __STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx)
2926 SET_BIT(USARTx->CR2, USART_CR2_LBDIE);
2930 * @brief Enable Error Interrupt
2931 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
2932 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
2933 * 0: Interrupt is inhibited
2934 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
2935 * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR
2936 * @param USARTx USART Instance
2937 * @retval None
2939 __STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx)
2941 SET_BIT(USARTx->CR3, USART_CR3_EIE);
2945 * @brief Enable CTS Interrupt
2946 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
2947 * Hardware Flow control feature is supported by the USARTx instance.
2948 * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS
2949 * @param USARTx USART Instance
2950 * @retval None
2952 __STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx)
2954 SET_BIT(USARTx->CR3, USART_CR3_CTSIE);
2958 #if defined(USART_TCBGT_SUPPORT)
2959 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
2961 * @brief Enable Smartcard Transmission Complete Before Guard Time Interrupt
2962 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
2963 * Smartcard feature is supported by the USARTx instance.
2964 * @rmtoll CR3 TCBGTIE LL_USART_EnableIT_TCBGT
2965 * @param USARTx USART Instance
2966 * @retval None
2968 __STATIC_INLINE void LL_USART_EnableIT_TCBGT(USART_TypeDef *USARTx)
2970 SET_BIT(USARTx->CR3, USART_CR3_TCBGTIE);
2972 #endif
2975 * @brief Disable IDLE Interrupt
2976 * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE
2977 * @param USARTx USART Instance
2978 * @retval None
2980 __STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx)
2982 CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE);
2986 * @brief Disable RX Not Empty Interrupt
2987 * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE
2988 * @param USARTx USART Instance
2989 * @retval None
2991 __STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx)
2993 CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE);
2997 * @brief Disable Transmission Complete Interrupt
2998 * @rmtoll CR1 TCIE LL_USART_DisableIT_TC
2999 * @param USARTx USART Instance
3000 * @retval None
3002 __STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx)
3004 CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE);
3008 * @brief Disable TX Empty Interrupt
3009 * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE
3010 * @param USARTx USART Instance
3011 * @retval None
3013 __STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx)
3015 CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE);
3019 * @brief Disable Parity Error Interrupt
3020 * @rmtoll CR1 PEIE LL_USART_DisableIT_PE
3021 * @param USARTx USART Instance
3022 * @retval None
3024 __STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx)
3026 CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE);
3030 * @brief Disable Character Match Interrupt
3031 * @rmtoll CR1 CMIE LL_USART_DisableIT_CM
3032 * @param USARTx USART Instance
3033 * @retval None
3035 __STATIC_INLINE void LL_USART_DisableIT_CM(USART_TypeDef *USARTx)
3037 CLEAR_BIT(USARTx->CR1, USART_CR1_CMIE);
3041 * @brief Disable Receiver Timeout Interrupt
3042 * @rmtoll CR1 RTOIE LL_USART_DisableIT_RTO
3043 * @param USARTx USART Instance
3044 * @retval None
3046 __STATIC_INLINE void LL_USART_DisableIT_RTO(USART_TypeDef *USARTx)
3048 CLEAR_BIT(USARTx->CR1, USART_CR1_RTOIE);
3052 * @brief Disable End Of Block Interrupt
3053 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3054 * Smartcard feature is supported by the USARTx instance.
3055 * @rmtoll CR1 EOBIE LL_USART_DisableIT_EOB
3056 * @param USARTx USART Instance
3057 * @retval None
3059 __STATIC_INLINE void LL_USART_DisableIT_EOB(USART_TypeDef *USARTx)
3061 CLEAR_BIT(USARTx->CR1, USART_CR1_EOBIE);
3065 * @brief Disable LIN Break Detection Interrupt
3066 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3067 * LIN feature is supported by the USARTx instance.
3068 * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD
3069 * @param USARTx USART Instance
3070 * @retval None
3072 __STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx)
3074 CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE);
3078 * @brief Disable Error Interrupt
3079 * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing
3080 * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_ISR register).
3081 * 0: Interrupt is inhibited
3082 * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_ISR register.
3083 * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR
3084 * @param USARTx USART Instance
3085 * @retval None
3087 __STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx)
3089 CLEAR_BIT(USARTx->CR3, USART_CR3_EIE);
3093 * @brief Disable CTS Interrupt
3094 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3095 * Hardware Flow control feature is supported by the USARTx instance.
3096 * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS
3097 * @param USARTx USART Instance
3098 * @retval None
3100 __STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx)
3102 CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE);
3106 #if defined(USART_TCBGT_SUPPORT)
3107 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
3109 * @brief Disable Smartcard Transmission Complete Before Guard Time Interrupt
3110 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3111 * Smartcard feature is supported by the USARTx instance.
3112 * @rmtoll CR3 TCBGTIE LL_USART_DisableIT_TCBGT
3113 * @param USARTx USART Instance
3114 * @retval None
3116 __STATIC_INLINE void LL_USART_DisableIT_TCBGT(USART_TypeDef *USARTx)
3118 CLEAR_BIT(USARTx->CR3, USART_CR3_TCBGTIE);
3120 #endif
3123 * @brief Check if the USART IDLE Interrupt source is enabled or disabled.
3124 * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE
3125 * @param USARTx USART Instance
3126 * @retval State of bit (1 or 0).
3128 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx)
3130 return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE));
3134 * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled.
3135 * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE
3136 * @param USARTx USART Instance
3137 * @retval State of bit (1 or 0).
3139 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx)
3141 return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE));
3145 * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled.
3146 * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC
3147 * @param USARTx USART Instance
3148 * @retval State of bit (1 or 0).
3150 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx)
3152 return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE));
3156 * @brief Check if the USART TX Empty Interrupt is enabled or disabled.
3157 * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE
3158 * @param USARTx USART Instance
3159 * @retval State of bit (1 or 0).
3161 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx)
3163 return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE));
3167 * @brief Check if the USART Parity Error Interrupt is enabled or disabled.
3168 * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE
3169 * @param USARTx USART Instance
3170 * @retval State of bit (1 or 0).
3172 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx)
3174 return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE));
3178 * @brief Check if the USART Character Match Interrupt is enabled or disabled.
3179 * @rmtoll CR1 CMIE LL_USART_IsEnabledIT_CM
3180 * @param USARTx USART Instance
3181 * @retval State of bit (1 or 0).
3183 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CM(USART_TypeDef *USARTx)
3185 return (READ_BIT(USARTx->CR1, USART_CR1_CMIE) == (USART_CR1_CMIE));
3189 * @brief Check if the USART Receiver Timeout Interrupt is enabled or disabled.
3190 * @rmtoll CR1 RTOIE LL_USART_IsEnabledIT_RTO
3191 * @param USARTx USART Instance
3192 * @retval State of bit (1 or 0).
3194 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RTO(USART_TypeDef *USARTx)
3196 return (READ_BIT(USARTx->CR1, USART_CR1_RTOIE) == (USART_CR1_RTOIE));
3200 * @brief Check if the USART End Of Block Interrupt is enabled or disabled.
3201 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3202 * Smartcard feature is supported by the USARTx instance.
3203 * @rmtoll CR1 EOBIE LL_USART_IsEnabledIT_EOB
3204 * @param USARTx USART Instance
3205 * @retval State of bit (1 or 0).
3207 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_EOB(USART_TypeDef *USARTx)
3209 return (READ_BIT(USARTx->CR1, USART_CR1_EOBIE) == (USART_CR1_EOBIE));
3213 * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled.
3214 * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not
3215 * LIN feature is supported by the USARTx instance.
3216 * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD
3217 * @param USARTx USART Instance
3218 * @retval State of bit (1 or 0).
3220 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx)
3222 return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE));
3226 * @brief Check if the USART Error Interrupt is enabled or disabled.
3227 * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR
3228 * @param USARTx USART Instance
3229 * @retval State of bit (1 or 0).
3231 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx)
3233 return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE));
3237 * @brief Check if the USART CTS Interrupt is enabled or disabled.
3238 * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not
3239 * Hardware Flow control feature is supported by the USARTx instance.
3240 * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS
3241 * @param USARTx USART Instance
3242 * @retval State of bit (1 or 0).
3244 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx)
3246 return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE));
3250 #if defined(USART_TCBGT_SUPPORT)
3251 /* Function available only on devices supporting Transmit Complete before Guard Time feature */
3253 * @brief Check if the Smartcard Transmission Complete Before Guard Time Interrupt is enabled or disabled.
3254 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3255 * Smartcard feature is supported by the USARTx instance.
3256 * @rmtoll CR3 TCBGTIE LL_USART_IsEnabledIT_TCBGT
3257 * @param USARTx USART Instance
3258 * @retval State of bit (1 or 0).
3260 __STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TCBGT(USART_TypeDef *USARTx)
3262 return (READ_BIT(USARTx->CR3, USART_CR3_TCBGTIE) == (USART_CR3_TCBGTIE));
3264 #endif
3267 * @}
3270 /** @defgroup USART_LL_EF_DMA_Management DMA_Management
3271 * @{
3275 * @brief Enable DMA Mode for reception
3276 * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX
3277 * @param USARTx USART Instance
3278 * @retval None
3280 __STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx)
3282 SET_BIT(USARTx->CR3, USART_CR3_DMAR);
3286 * @brief Disable DMA Mode for reception
3287 * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX
3288 * @param USARTx USART Instance
3289 * @retval None
3291 __STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx)
3293 CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR);
3297 * @brief Check if DMA Mode is enabled for reception
3298 * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX
3299 * @param USARTx USART Instance
3300 * @retval State of bit (1 or 0).
3302 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx)
3304 return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR));
3308 * @brief Enable DMA Mode for transmission
3309 * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX
3310 * @param USARTx USART Instance
3311 * @retval None
3313 __STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx)
3315 SET_BIT(USARTx->CR3, USART_CR3_DMAT);
3319 * @brief Disable DMA Mode for transmission
3320 * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX
3321 * @param USARTx USART Instance
3322 * @retval None
3324 __STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx)
3326 CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT);
3330 * @brief Check if DMA Mode is enabled for transmission
3331 * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX
3332 * @param USARTx USART Instance
3333 * @retval State of bit (1 or 0).
3335 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx)
3337 return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT));
3341 * @brief Enable DMA Disabling on Reception Error
3342 * @rmtoll CR3 DDRE LL_USART_EnableDMADeactOnRxErr
3343 * @param USARTx USART Instance
3344 * @retval None
3346 __STATIC_INLINE void LL_USART_EnableDMADeactOnRxErr(USART_TypeDef *USARTx)
3348 SET_BIT(USARTx->CR3, USART_CR3_DDRE);
3352 * @brief Disable DMA Disabling on Reception Error
3353 * @rmtoll CR3 DDRE LL_USART_DisableDMADeactOnRxErr
3354 * @param USARTx USART Instance
3355 * @retval None
3357 __STATIC_INLINE void LL_USART_DisableDMADeactOnRxErr(USART_TypeDef *USARTx)
3359 CLEAR_BIT(USARTx->CR3, USART_CR3_DDRE);
3363 * @brief Indicate if DMA Disabling on Reception Error is disabled
3364 * @rmtoll CR3 DDRE LL_USART_IsEnabledDMADeactOnRxErr
3365 * @param USARTx USART Instance
3366 * @retval State of bit (1 or 0).
3368 __STATIC_INLINE uint32_t LL_USART_IsEnabledDMADeactOnRxErr(USART_TypeDef *USARTx)
3370 return (READ_BIT(USARTx->CR3, USART_CR3_DDRE) == (USART_CR3_DDRE));
3374 * @brief Get the data register address used for DMA transfer
3375 * @rmtoll RDR RDR LL_USART_DMA_GetRegAddr\n
3376 * @rmtoll TDR TDR LL_USART_DMA_GetRegAddr
3377 * @param USARTx USART Instance
3378 * @param Direction This parameter can be one of the following values:
3379 * @arg @ref LL_USART_DMA_REG_DATA_TRANSMIT
3380 * @arg @ref LL_USART_DMA_REG_DATA_RECEIVE
3381 * @retval Address of data register
3383 __STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx, uint32_t Direction)
3385 register uint32_t data_reg_addr = 0U;
3387 if (Direction == LL_USART_DMA_REG_DATA_TRANSMIT)
3389 /* return address of TDR register */
3390 data_reg_addr = (uint32_t) &(USARTx->TDR);
3392 else
3394 /* return address of RDR register */
3395 data_reg_addr = (uint32_t) &(USARTx->RDR);
3398 return data_reg_addr;
3402 * @}
3405 /** @defgroup USART_LL_EF_Data_Management Data_Management
3406 * @{
3410 * @brief Read Receiver Data register (Receive Data value, 8 bits)
3411 * @rmtoll RDR RDR LL_USART_ReceiveData8
3412 * @param USARTx USART Instance
3413 * @retval Value between Min_Data=0x00 and Max_Data=0xFF
3415 __STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx)
3417 return (uint8_t)(READ_BIT(USARTx->RDR, USART_RDR_RDR));
3421 * @brief Read Receiver Data register (Receive Data value, 9 bits)
3422 * @rmtoll RDR RDR LL_USART_ReceiveData9
3423 * @param USARTx USART Instance
3424 * @retval Value between Min_Data=0x00 and Max_Data=0x1FF
3426 __STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx)
3428 return (uint16_t)(READ_BIT(USARTx->RDR, USART_RDR_RDR));
3432 * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits)
3433 * @rmtoll TDR TDR LL_USART_TransmitData8
3434 * @param USARTx USART Instance
3435 * @param Value between Min_Data=0x00 and Max_Data=0xFF
3436 * @retval None
3438 __STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value)
3440 USARTx->TDR = Value;
3444 * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits)
3445 * @rmtoll TDR TDR LL_USART_TransmitData9
3446 * @param USARTx USART Instance
3447 * @param Value between Min_Data=0x00 and Max_Data=0x1FF
3448 * @retval None
3450 __STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value)
3452 USARTx->TDR = Value & 0x1FFU;
3456 * @}
3459 /** @defgroup USART_LL_EF_Execution Execution
3460 * @{
3464 * @brief Request an Automatic Baud Rate measurement on next received data frame
3465 * @note Macro @ref IS_USART_AUTOBAUDRATE_DETECTION_INSTANCE(USARTx) can be used to check whether or not
3466 * Auto Baud Rate detection feature is supported by the USARTx instance.
3467 * @rmtoll RQR ABRRQ LL_USART_RequestAutoBaudRate
3468 * @param USARTx USART Instance
3469 * @retval None
3471 __STATIC_INLINE void LL_USART_RequestAutoBaudRate(USART_TypeDef *USARTx)
3473 SET_BIT(USARTx->RQR, USART_RQR_ABRRQ);
3477 * @brief Request Break sending
3478 * @rmtoll RQR SBKRQ LL_USART_RequestBreakSending
3479 * @param USARTx USART Instance
3480 * @retval None
3482 __STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx)
3484 SET_BIT(USARTx->RQR, USART_RQR_SBKRQ);
3488 * @brief Put USART in mute mode and set the RWU flag
3489 * @rmtoll RQR MMRQ LL_USART_RequestEnterMuteMode
3490 * @param USARTx USART Instance
3491 * @retval None
3493 __STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx)
3495 SET_BIT(USARTx->RQR, USART_RQR_MMRQ);
3499 * @brief Request a Receive Data flush
3500 * @rmtoll RQR RXFRQ LL_USART_RequestRxDataFlush
3501 * @param USARTx USART Instance
3502 * @retval None
3504 __STATIC_INLINE void LL_USART_RequestRxDataFlush(USART_TypeDef *USARTx)
3506 SET_BIT(USARTx->RQR, USART_RQR_RXFRQ);
3510 * @brief Request a Transmit data flush
3511 * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not
3512 * Smartcard feature is supported by the USARTx instance.
3513 * @rmtoll RQR TXFRQ LL_USART_RequestTxDataFlush
3514 * @param USARTx USART Instance
3515 * @retval None
3517 __STATIC_INLINE void LL_USART_RequestTxDataFlush(USART_TypeDef *USARTx)
3519 SET_BIT(USARTx->RQR, USART_RQR_TXFRQ);
3523 * @}
3526 #if defined(USE_FULL_LL_DRIVER)
3527 /** @defgroup USART_LL_EF_Init Initialization and de-initialization functions
3528 * @{
3530 ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx);
3531 ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct);
3532 void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct);
3533 ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct);
3534 void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct);
3536 * @}
3538 #endif /* USE_FULL_LL_DRIVER */
3541 * @}
3545 * @}
3548 #endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 */
3551 * @}
3554 #ifdef __cplusplus
3556 #endif
3558 #endif /* __STM32F7xx_LL_USART_H */
3560 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/