before merging master
[inav.git] / lib / main / AT32F43x / Drivers / AT32F43x_StdPeriph_Driver / src / at32f435_437_usart.c
blobeb3b75282face1033ebd1e419c512e7e22179bec
1 /**
2 **************************************************************************
3 * @file at32f435_437_usart.c
4 * @version v2.1.0
5 * @date 2022-08-16
6 * @brief contains all the functions for the usart firmware library
7 **************************************************************************
8 * Copyright notice & Disclaimer
10 * The software Board Support Package (BSP) that is made available to
11 * download from Artery official website is the copyrighted work of Artery.
12 * Artery authorizes customers to use, copy, and distribute the BSP
13 * software and its related documentation for the purpose of design and
14 * development in conjunction with Artery microcontrollers. Use of the
15 * software is governed by this copyright notice and the following disclaimer.
17 * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
18 * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
19 * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
20 * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
21 * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
22 * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
24 **************************************************************************
27 /* includes ------------------------------------------------------------------*/
28 #include "at32f435_437_conf.h"
30 /** @addtogroup AT32F435_437_periph_driver
31 * @{
34 /** @defgroup USART
35 * @brief USART driver modules
36 * @{
39 #ifdef USART_MODULE_ENABLED
41 /** @defgroup USART_private_functions
42 * @{
45 /**
46 * @brief deinitialize the usart peripheral registers to their default reset values.
47 * @param usart_x: select the usart or the uart peripheral.
48 * this parameter can be one of the following values:
49 * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8.
50 * @retval none
52 void usart_reset(usart_type* usart_x)
54 if(usart_x == USART1)
56 crm_periph_reset(CRM_USART1_PERIPH_RESET, TRUE);
57 crm_periph_reset(CRM_USART1_PERIPH_RESET, FALSE);
59 else if(usart_x == USART2)
61 crm_periph_reset(CRM_USART2_PERIPH_RESET, TRUE);
62 crm_periph_reset(CRM_USART2_PERIPH_RESET, FALSE);
64 else if(usart_x == USART3)
66 crm_periph_reset(CRM_USART3_PERIPH_RESET, TRUE);
67 crm_periph_reset(CRM_USART3_PERIPH_RESET, FALSE);
69 else if(usart_x == UART4)
71 crm_periph_reset(CRM_UART4_PERIPH_RESET, TRUE);
72 crm_periph_reset(CRM_UART4_PERIPH_RESET, FALSE);
74 else if(usart_x == UART5)
76 crm_periph_reset(CRM_UART5_PERIPH_RESET, TRUE);
77 crm_periph_reset(CRM_UART5_PERIPH_RESET, FALSE);
79 else if(usart_x == USART6)
81 crm_periph_reset(CRM_USART6_PERIPH_RESET, TRUE);
82 crm_periph_reset(CRM_USART6_PERIPH_RESET, FALSE);
84 else if(usart_x == UART7)
86 crm_periph_reset(CRM_UART7_PERIPH_RESET, TRUE);
87 crm_periph_reset(CRM_UART7_PERIPH_RESET, FALSE);
89 else if(usart_x == UART8)
91 crm_periph_reset(CRM_UART8_PERIPH_RESET, TRUE);
92 crm_periph_reset(CRM_UART8_PERIPH_RESET, FALSE);
96 /**
97 * @brief initialize the usart peripheral according to the specified parameters.
98 * @param usart_x: select the usart or the uart peripheral.
99 * this parameter can be one of the following values:
100 * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8.
101 * @param baud_rate: configure the usart communication baud rate.
102 * @param data_bit: data bits transmitted or received in a frame
103 * this parameter can be one of the following values:
104 * - USART_DATA_7BITS
105 * - USART_DATA_8BITS
106 * - USART_DATA_9BITS.
107 * @param stop_bit: stop bits transmitted
108 * this parameter can be one of the following values:
109 * - USART_STOP_1_BIT
110 * - USART_STOP_0_5_BIT.
111 * - USART_STOP_2_BIT
112 * - USART_STOP_1_5_BIT.
113 * @retval none
115 void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit)
117 crm_clocks_freq_type clocks_freq;
118 uint32_t apb_clock, temp_val;
119 crm_clocks_freq_get(&clocks_freq);
120 if((usart_x == USART1) || (usart_x == USART6))
122 apb_clock = clocks_freq.apb2_freq;
124 else
126 apb_clock = clocks_freq.apb1_freq;
128 temp_val = (apb_clock * 10 / baud_rate);
129 if((temp_val % 10) < 5)
131 temp_val = (temp_val / 10);
133 else
135 temp_val = (temp_val / 10) + 1;
137 usart_x->baudr_bit.div = temp_val;
138 if(data_bit == USART_DATA_7BITS)
140 usart_x->ctrl1_bit.dbn_h = 1;
141 usart_x->ctrl1_bit.dbn_l = 0;
143 else if(data_bit == USART_DATA_8BITS)
145 usart_x->ctrl1_bit.dbn_h = 0;
146 usart_x->ctrl1_bit.dbn_l = 0;
148 else
150 usart_x->ctrl1_bit.dbn_h = 0;
151 usart_x->ctrl1_bit.dbn_l = 1;
153 usart_x->ctrl2_bit.stopbn = stop_bit;
157 * @brief usart parity selection config.
158 * @param usart_x: select the usart or the uart peripheral.
159 * this parameter can be one of the following values:
160 * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8.
161 * @param parity: select the none, odd or even parity.
162 * this parameter can be one of the following values:
163 * - USART_PARITY_NONE
164 * - USART_PARITY_EVEN.
165 * - USART_PARITY_ODD
166 * @retval none
168 void usart_parity_selection_config(usart_type* usart_x, usart_parity_selection_type parity)
170 if(parity == USART_PARITY_NONE)
172 usart_x->ctrl1_bit.psel = FALSE;
173 usart_x->ctrl1_bit.pen = FALSE;
175 else if(parity == USART_PARITY_EVEN)
177 usart_x->ctrl1_bit.psel = FALSE;
178 usart_x->ctrl1_bit.pen = TRUE;
180 else if(parity == USART_PARITY_ODD)
182 usart_x->ctrl1_bit.psel = TRUE;
183 usart_x->ctrl1_bit.pen = TRUE;
188 * @brief enable or disable the specified usart peripheral.
189 * @param usart_x: select the usart or the uart peripheral.
190 * this parameter can be one of the following values:
191 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
192 * @param new_state: new state of the usart peripheral.
193 * this parameter can be: TRUE or FALSE.
194 * @retval none
196 void usart_enable(usart_type* usart_x, confirm_state new_state)
198 usart_x->ctrl1_bit.uen = new_state;
202 * @brief usart transmitter enable.
203 * @param usart_x: select the usart or the uart peripheral.
204 * this parameter can be one of the following values:
205 * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8.
206 * @param new_state: TRUE or FALSE.
207 * @retval none
209 void usart_transmitter_enable(usart_type* usart_x, confirm_state new_state)
211 usart_x->ctrl1_bit.ten = new_state;
215 * @brief usart receiver enable.
216 * @param usart_x: select the usart or the uart peripheral.
217 * this parameter can be one of the following values:
218 * USART1, USART2, USART3, UART4 ,UART5, USART6, UART7 or UART8.
219 * @param new_state: TRUE or FALSE.
220 * @retval none
222 void usart_receiver_enable(usart_type* usart_x, confirm_state new_state)
224 usart_x->ctrl1_bit.ren = new_state;
228 * @brief usart clock config.
229 * @note clock config are not available for UART4, UART5, UART7 and UART8.
230 * @param usart_x: select the usart or the uart peripheral.
231 * this parameter can be one of the following values:
232 * USART1, USART2, USART3 or USART6.
233 * @param clk_pol: polarity of the clock output on the ck pin.
234 * this parameter can be one of the following values:
235 * - USART_CLOCK_POLARITY_LOW
236 * - USART_CLOCK_POLARITY_HIGH
237 * @param clk_pha: phase of the clock output on the ck pin.
238 * this parameter can be one of the following values:
239 * - USART_CLOCK_PHASE_1EDGE
240 * - USART_CLOCK_PHASE_2EDGE
241 * @param clk_lb: whether the clock pulse of the last data bit transmitted (MSB) is outputted on the ck pin.
242 * this parameter can be one of the following values:
243 * - USART_CLOCK_LAST_BIT_NONE
244 * - USART_CLOCK_LAST_BIT_OUTPUT
245 * @retval none
247 void usart_clock_config(usart_type* usart_x, usart_clock_polarity_type clk_pol, usart_clock_phase_type clk_pha, usart_lbcp_type clk_lb)
249 usart_x->ctrl2_bit.clkpol = clk_pol;
250 usart_x->ctrl2_bit.clkpha = clk_pha;
251 usart_x->ctrl2_bit.lbcp = clk_lb;
255 * @brief usart enable the ck pin.
256 * @note clock enable are not available for UART4, UART5, UART7 and UART8.
257 * @param usart_x: select the usart or the uart peripheral.
258 * this parameter can be one of the following values:
259 * USART1, USART2, USART3 or USART6.
260 * @param new_state: TRUE or FALSE
261 * @retval none
263 void usart_clock_enable(usart_type* usart_x, confirm_state new_state)
265 usart_x->ctrl2_bit.clken = new_state;
269 * @brief enable or disable the specified usart interrupts.
270 * @param usart_x: select the usart or the uart peripheral.
271 * this parameter can be one of the following values:
272 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
273 * @param usart_int: specifies the USART interrupt sources to be enabled or disabled.
274 * this parameter can be one of the following values:
275 * - USART_IDLE_INT: idle interrupt
276 * - USART_RDBF_INT: rdbf interrupt
277 * - USART_TDC_INT: tdc interrupt
278 * - USART_TDBE_INT: tdbe interrupt
279 * - USART_PERR_INT: perr interrupt
280 * - USART_BF_INT: break frame interrupt
281 * - USART_ERR_INT: err interrupt
282 * - USART_CTSCF_INT: ctscf interrupt
283 * @param new_state: new state of the specified usart interrupts.
284 * this parameter can be: TRUE or FALSE.
285 * @retval none
287 void usart_interrupt_enable(usart_type* usart_x, uint32_t usart_int, confirm_state new_state)
289 if(new_state == TRUE)
290 PERIPH_REG((uint32_t)usart_x, usart_int) |= PERIPH_REG_BIT(usart_int);
291 else
292 PERIPH_REG((uint32_t)usart_x, usart_int) &= ~PERIPH_REG_BIT(usart_int);
296 * @brief enable or disable the usart's dma transmitter interface.
297 * @param usart_x: select the usart or the uart peripheral.
298 * this parameter can be one of the following values:
299 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
300 * @param new_state: new state of the dma request sources.
301 * this parameter can be: TRUE or FALSE.
302 * @retval none
304 void usart_dma_transmitter_enable(usart_type* usart_x, confirm_state new_state)
306 usart_x->ctrl3_bit.dmaten = new_state;
310 * @brief enable or disable the usart's dma receiver interface.
311 * @param usart_x: select the usart or the uart peripheral.
312 * this parameter can be one of the following values:
313 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
314 * @param new_state: new state of the dma request sources.
315 * this parameter can be: TRUE or FALSE.
316 * @retval none
318 void usart_dma_receiver_enable(usart_type* usart_x, confirm_state new_state)
320 usart_x->ctrl3_bit.dmaren = new_state;
324 * @brief set the wakeup id of the usart.
325 * @param usart_x: select the usart or the uart peripheral.
326 * this parameter can be one of the following values:
327 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
328 * @param usart_id: the matching id(0x0~0xFF).
329 * @retval none
331 void usart_wakeup_id_set(usart_type* usart_x, uint8_t usart_id)
333 if(usart_x->ctrl2_bit.idbn == USART_ID_FIXED_4_BIT)
335 usart_x->ctrl2_bit.id_l = (usart_id & 0x0F);
336 usart_x->ctrl2_bit.id_h = 0;
338 else
340 usart_x->ctrl2_bit.id_l = (usart_id & 0x0F);
341 usart_x->ctrl2_bit.id_h = ((usart_id & 0xF0) >> 4);
346 * @brief select the usart wakeup method in multi-processor communication.
347 * @param usart_x: select the usart or the uart peripheral.
348 * this parameter can be one of the following values:
349 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
350 * @param wakeup_mode: determines the way to wake up usart method.
351 * this parameter can be one of the following values:
352 * - USART_WAKEUP_BY_IDLE_FRAME
353 * - USART_WAKEUP_BY_MATCHING_ID
354 * @retval none
356 void usart_wakeup_mode_set(usart_type* usart_x, usart_wakeup_mode_type wakeup_mode)
358 usart_x->ctrl1_bit.wum = wakeup_mode;
362 * @brief config the usart in mute mode in multi-processor communication.
363 * @param usart_x: select the usart or the uart peripheral.
364 * this parameter can be one of the following values:
365 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
366 * @param new_state: new state of the usart mute mode.
367 * this parameter can be: TRUE or FALSE.
368 * @retval none
370 void usart_receiver_mute_enable(usart_type* usart_x, confirm_state new_state)
372 usart_x->ctrl1_bit.rm = new_state;
376 * @brief set the usart break frame bit num.
377 * @param usart_x: select the usart or the uart peripheral.
378 * this parameter can be one of the following values:
379 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
380 * @param break_bit: specifies the break bit num.
381 * this parameter can be one of the following values:
382 * - USART_BREAK_10BITS
383 * - USART_BREAK_11BITS
384 * @retval none
386 void usart_break_bit_num_set(usart_type* usart_x, usart_break_bit_num_type break_bit)
388 usart_x->ctrl2_bit.bfbn = break_bit;
392 * @brief enable or disable the usart lin mode.
393 * @param usart_x: select the usart or the uart peripheral.
394 * this parameter can be one of the following values:
395 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
396 * @param new_state: new state of the usart lin mode.
397 * this parameter can be: TRUE or FALSE.
398 * @retval none
400 void usart_lin_mode_enable(usart_type* usart_x, confirm_state new_state)
402 usart_x->ctrl2_bit.linen = new_state;
406 * @brief transmit single data through the usart peripheral.
407 * @param usart_x: select the usart or the uart peripheral.
408 * this parameter can be one of the following values:
409 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
410 * @param data: the data to transmit.
411 * @retval none
413 void usart_data_transmit(usart_type* usart_x, uint16_t data)
415 usart_x->dt = (data & 0x01FF);
419 * @brief return the most recent received data by the usart peripheral.
420 * @param usart_x: select the usart or the uart peripheral.
421 * this parameter can be one of the following values:
422 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
423 * @retval the received data.
425 uint16_t usart_data_receive(usart_type* usart_x)
427 return (uint16_t)(usart_x->dt);
431 * @brief transmit break characters.
432 * @param usart_x: select the usart or the uart peripheral.
433 * this parameter can be one of the following values:
434 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
435 * @retval none
437 void usart_break_send(usart_type* usart_x)
439 usart_x->ctrl1_bit.sbf = TRUE;
443 * @brief config the specified usart smartcard guard time.
444 * @note The guard time bits are not available for UART4, UART5, UART7 or UART8.
445 * @param usart_x: select the usart or the uart peripheral.
446 * this parameter can be one of the following values:
447 * USART1, USART2, USART3 or USART6.
448 * @param guard_time_val: specifies the guard time (0x00~0xFF).
449 * @retval none
451 void usart_smartcard_guard_time_set(usart_type* usart_x, uint8_t guard_time_val)
453 usart_x->gdiv_bit.scgt = guard_time_val;
457 * @brief config the irda/smartcard division.
458 * @note the division are not available for UART4, UART5, UART7 or UART8.
459 * @param usart_x: select the usart or the uart peripheral.
460 * this parameter can be one of the following values:
461 * USART1, USART2, USART3 or USART6.
462 * @param div_val: specifies the division.
463 * @retval none
465 void usart_irda_smartcard_division_set(usart_type* usart_x, uint8_t div_val)
467 usart_x->gdiv_bit.isdiv = div_val;
471 * @brief enable or disable the usart smart card mode.
472 * @note the smart card mode are not available for UART4, UART5, UART7 or UART8.
473 * @param usart_x: select the usart or the uart peripheral.
474 * this parameter can be one of the following values:
475 * USART1, USART2, USART3 or USART6.
476 * @param new_state: new state of the smart card mode.
477 * this parameter can be: TRUE or FALSE.
478 * @retval none
480 void usart_smartcard_mode_enable(usart_type* usart_x, confirm_state new_state)
482 usart_x->ctrl3_bit.scmen = new_state;
486 * @brief enable or disable nack transmission in smartcard mode.
487 * @note the smart card nack are not available for UART4, UART5, UART7 or UART8.
488 * @param usart_x: select the usart or the uart peripheral.
489 * this parameter can be one of the following values:
490 * USART1, USART2, USART3 or USART6.
491 * @param new_state: new state of the nack transmission.
492 * this parameter can be: TRUE or FALSE.
493 * @retval none
495 void usart_smartcard_nack_set(usart_type* usart_x, confirm_state new_state)
497 usart_x->ctrl3_bit.scnacken = new_state;
501 * @brief enable or disable the usart single line bidirectional half-duplex communication.
502 * @param usart_x: select the usart or the uart peripheral.
503 * this parameter can be one of the following values:
504 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
505 * @param new_state: new state of the single line half-duplex select.
506 * this parameter can be: TRUE or FALSE.
507 * @retval none
509 void usart_single_line_halfduplex_select(usart_type* usart_x, confirm_state new_state)
511 usart_x->ctrl3_bit.slben = new_state;
515 * @brief enable or disable the usart's irda interface.
516 * @param usart_x: select the usart or the uart peripheral.
517 * this parameter can be one of the following values:
518 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
519 * @param new_state: new state of the irda mode.
520 * this parameter can be: TRUE or FALSE.
521 * @retval none
523 void usart_irda_mode_enable(usart_type* usart_x, confirm_state new_state)
525 usart_x->ctrl3_bit.irdaen = new_state;
529 * @brief configure the usart's irda low power.
530 * @param usart_x: select the usart or the uart peripheral.
531 * this parameter can be one of the following values:
532 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
533 * @param new_state: new state of the irda mode.
534 * this parameter can be: TRUE or FALSE.
535 * @retval none
537 void usart_irda_low_power_enable(usart_type* usart_x, confirm_state new_state)
539 usart_x->ctrl3_bit.irdalp = new_state;
543 * @brief configure the usart's hardware flow control.
544 * @param usart_x: select the usart or the uart peripheral.
545 * this parameter can be one of the following values:
546 * USART1, USART2, USART3
547 * @param flow_state: specifies the hardware flow control.
548 * this parameter can be one of the following values:
549 * - USART_HARDWARE_FLOW_NONE
550 * - USART_HARDWARE_FLOW_RTS,
551 * - USART_HARDWARE_FLOW_CTS,
552 * - USART_HARDWARE_FLOW_RTS_CTS
553 * @retval none
555 void usart_hardware_flow_control_set(usart_type* usart_x,usart_hardware_flow_control_type flow_state)
557 if(flow_state == USART_HARDWARE_FLOW_NONE)
559 usart_x->ctrl3_bit.rtsen = FALSE;
560 usart_x->ctrl3_bit.ctsen = FALSE;
562 else if(flow_state == USART_HARDWARE_FLOW_RTS)
564 usart_x->ctrl3_bit.rtsen = TRUE;
565 usart_x->ctrl3_bit.ctsen = FALSE;
567 else if(flow_state == USART_HARDWARE_FLOW_CTS)
569 usart_x->ctrl3_bit.rtsen = FALSE;
570 usart_x->ctrl3_bit.ctsen = TRUE;
572 else if(flow_state == USART_HARDWARE_FLOW_RTS_CTS)
574 usart_x->ctrl3_bit.rtsen = TRUE;
575 usart_x->ctrl3_bit.ctsen = TRUE;
580 * @brief check whether the specified usart flag is set or not.
581 * @param usart_x: select the usart or the uart peripheral.
582 * this parameter can be one of the following values:
583 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
584 * @param flag: specifies the flag to check.
585 * this parameter can be one of the following values:
586 * - USART_CTSCF_FLAG: cts change flag (not available for UART4,UART5,USART6,UART7 and UART8)
587 * - USART_BFF_FLAG: break frame flag
588 * - USART_TDBE_FLAG: transmit data buffer empty flag
589 * - USART_TDC_FLAG: transmit data complete flag
590 * - USART_RDBF_FLAG: receive data buffer full flag
591 * - USART_IDLEF_FLAG: idle flag
592 * - USART_ROERR_FLAG: receiver overflow error flag
593 * - USART_NERR_FLAG: noise error flag
594 * - USART_FERR_FLAG: framing error flag
595 * - USART_PERR_FLAG: parity error flag
596 * @retval the new state of usart_flag (SET or RESET).
598 flag_status usart_flag_get(usart_type* usart_x, uint32_t flag)
600 if(usart_x->sts & flag)
602 return SET;
604 else
606 return RESET;
611 * @brief clear the usart's pending flags.
612 * @param usart_x: select the usart or the uart peripheral.
613 * this parameter can be one of the following values:
614 * USART1, USART2, USART3, UART4, UART5, USART6, UART7 or UART8.
615 * @param flag: specifies the flag to clear.
616 * this parameter can be any combination of the following values:
617 * - USART_CTSCF_FLAG: (not available for UART4,UART5,USART6,UART7 and UART8).
618 * - USART_BFF_FLAG:
619 * - USART_TDC_FLAG:
620 * - USART_RDBF_FLAG:
621 * - USART_PERR_FLAG:
622 * - USART_FERR_FLAG:
623 * - USART_NERR_FLAG:
624 * - USART_ROERR_FLAG:
625 * - USART_IDLEF_FLAG:
626 * @note
627 * - USART_PERR_FLAG, USART_FERR_FLAG, USART_NERR_FLAG, USART_ROERR_FLAG and USART_IDLEF_FLAG are cleared by software
628 * sequence: a read operation to usart sts register (usart_flag_get())
629 * followed by a read operation to usart dt register (usart_data_receive()).
630 * - USART_RDBF_FLAG can be also cleared by a read to the usart dt register(usart_data_receive()).
631 * - USART_TDC_FLAG can be also cleared by software sequence: a read operation to usart sts register (usart_flag_get())
632 * followed by a write operation to usart dt register (usart_data_transmit()).
633 * - USART_TDBE_FLAG is cleared only by a write to the usart dt register(usart_data_transmit()).
634 * @retval none
636 void usart_flag_clear(usart_type* usart_x, uint32_t flag)
638 if(flag & (USART_PERR_FLAG | USART_FERR_FLAG | USART_NERR_FLAG | USART_ROERR_FLAG | USART_IDLEF_FLAG))
640 UNUSED(usart_x->sts);
641 UNUSED(usart_x->dt);
643 else
645 usart_x->sts = ~flag;
650 * @brief configure the usart's rs485 transmit delay time.
651 * @param usart_x: select the usart or the uart peripheral.
652 * this parameter can be one of the following values:
653 * USART1, USART2, USART3
654 * @param start_delay_time: transmit start delay time.
655 * @param complete_delay_time: transmit complete delay time.
656 * @retval none
658 void usart_rs485_delay_time_config(usart_type* usart_x, uint8_t start_delay_time, uint8_t complete_delay_time)
660 usart_x->ctrl1_bit.tsdt = start_delay_time;
661 usart_x->ctrl1_bit.tcdt = complete_delay_time;
665 * @brief swap the usart's transmit receive pin.
666 * @param usart_x: select the usart or the uart peripheral.
667 * this parameter can be one of the following values:
668 * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8.
669 * @param new_state: new state of the usart peripheral.
670 * this parameter can be: TRUE or FALSE.
671 * @retval none
673 void usart_transmit_receive_pin_swap(usart_type* usart_x, confirm_state new_state)
675 usart_x->ctrl2_bit.trpswap = new_state;
679 * @brief set the usart's identification bit num.
680 * @param usart_x: select the usart or the uart peripheral.
681 * this parameter can be one of the following values:
682 * USART1, USART2, USART3, UART4, UART5, USART6, UART7,or UART8.
683 * @param id_bit_num: the usart wakeup identification bit num.
684 * this parameter can be: USART_ID_FIXED_4_BIT or USART_ID_RELATED_DATA_BIT.
685 * @retval none
687 void usart_id_bit_num_set(usart_type* usart_x, usart_identification_bit_num_type id_bit_num)
689 usart_x->ctrl2_bit.idbn = (uint8_t)id_bit_num;
693 * @brief set the usart's de polarity.
694 * @param usart_x: select the usart or the uart peripheral.
695 * this parameter can be one of the following values:
696 * USART1, USART2, USART3
697 * @param de_polarity: the usart de polarity selection.
698 * this parameter can be: USART_DE_POLARITY_HIGH or USART_DE_POLARITY_LOW.
699 * @retval none
701 void usart_de_polarity_set(usart_type* usart_x, usart_de_polarity_type de_polarity)
703 usart_x->ctrl3_bit.dep = (uint8_t)de_polarity;
707 * @brief enable or disable the usart's rs485 mode.
708 * @param usart_x: select the usart or the uart peripheral.
709 * this parameter can be one of the following values:
710 * USART1, USART2, USART3
711 * @param new_state: new state of the irda mode.
712 * this parameter can be: TRUE or FALSE.
713 * @retval none
715 void usart_rs485_mode_enable(usart_type* usart_x, confirm_state new_state)
717 usart_x->ctrl3_bit.rs485en = new_state;
721 * @}
724 #endif
727 * @}
731 * @}