当前位置:网站首页>Esp32 (UART event) - serial port event learning (1)

Esp32 (UART event) - serial port event learning (1)

2022-04-23 18:40:00 Please call me Xiao Peng

Tips : This blog serves as a learning note , If there are mistakes, I hope to correct them

One 、ESP32 Introduction of serial port

  UART Is a character oriented universal data link , Communication between devices can be realized . Asynchronous transmission means that there is no need to add clock information to the transmitted data . This also requires the rate of the sender and receiver 、 Stop bit 、 Parity bits, etc. should be the same , Communication can succeed .
   A typical UART The frame starts at a start bit , This is followed by valid data , Then the parity bit ( not essential ), Finally, the stop bit .
  ESP32 Upper UART The controller supports a variety of character lengths and stop bits . in addition , The controller also supports software and hardware flow control and control DMA, It can realize seamless high-speed data transmission . Developers can use multiple UART port , At the same time, it can ensure little software overhead .
  ESP32 There's... In the chip 3 individual UART The controller is available , And compatible with different UART equipment . in addition ,UART It can also be used for infrared data exchange (IrDA) or RS-485 modems .
• Programmable baud rate
• 3 individual UART Sending of FIFO And receiving FIFO share 1024 × 8-bit RAM
• Full duplex asynchronous communication
• Support baud rate self-test function of input signal
• Support 5/6/7/8 Bit data length
• Support 1/1.5/2/3 Stop bits
• Support parity bit
• Support RS485 agreement
• Support IrDA agreement
• Support DMA High speed data communication
• Support UART Wake up mode
• Support software flow control and hardware flow control
   It is worth noting that ESP32 In the three-way serial port 0 Pin modification is not supported. The default is RGIO1 As RX,GPIO3 As TX, When configuring, you need to pay attention to , A serial port 0 By default, it is used as a download program ESP_LOG Output .UART1 The default pin is GPIO9 Used as a U1RXD,GPIO10 Used as a U1TXD, But these two pins are also used for external connection flash Of , So in use UART1 You need to set other pins when you need to ,UART2 The default pin is GPIO16 Used as a U2RXD,GPIO17 Used as a U2TXD.

Two 、 Hardware design

   The hardware settings here use M5Stack Hardware to realize the experimental demonstration of serial communication protocol .
 Insert picture description here

3、 ... and 、 Implementation code

   What is used here is official uart_event_example_main Of Demo Demonstrate the experimental results . The initialization process data is as follows .esp32 The realization of serial port event in is realized by receiving queue , By registering the event queue when installing the serial port driver , Wait for the queue to receive serial port events in the task .
 Insert picture description here

    The initialization code is as follows 
/* UART Events Example This example code is in the Public Domain (or CC0 licensed, at your option.) Unless required by applicable law or agreed to in writing, this software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. */
#include <stdio.h>
#include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "driver/uart.h"
#include "esp_log.h"

static const char *TAG = "uart_events";

/** * This example shows how to use the UART driver to handle special UART events. * * It also reads data from UART0 directly, and echoes it to console. * * - Port: UART0 * - Receive (Rx) buffer: on * - Transmit (Tx) buffer: off * - Flow control: off * - Event queue: on * - Pin assignment: TxD (default), RxD (default) */

#define EX_UART_NUM UART_NUM_0 // Define serial port number macro definition 
#define PATTERN_CHR_NUM (3) /*!< Set the number of consecutive and identical characters received by receiver which defines a UART pattern*/

#define BUF_SIZE (1024) //buf size 
#define RD_BUF_SIZE (BUF_SIZE) // Read character size 
static QueueHandle_t uart0_queue;       // Serial port queue 

static void uart_event_task(void *pvParameters)
{
    
    uart_event_t event;
    size_t buffered_size;
    uint8_t* dtmp = (uint8_t*) malloc(RD_BUF_SIZE); // Dynamic request memory 
    for(;;) {
    
        //Waiting for UART event.  Wait for serial port event queue 
        if(xQueueReceive(uart0_queue, (void * )&event, (portTickType)portMAX_DELAY)) {
    
            bzero(dtmp, RD_BUF_SIZE);               // Clear the queue of dynamic applications 
            ESP_LOGI(TAG, "uart[%d] event:", EX_UART_NUM);
            switch(event.type) {
    
                /* We'd better deal with data events quickly , There will be more data events than other types   Events . If we spend too much time on data events , The queue may be full of .*/
                case UART_DATA:                     // UART Event to receive data 
                    ESP_LOGI(TAG, "[UART DATA]: %d", event.size);
                    uart_read_bytes(EX_UART_NUM, dtmp, event.size, portMAX_DELAY);  // get data 
                    ESP_LOGI(TAG, "[DATA EVT]:");
                    uart_write_bytes(EX_UART_NUM, (const char*) dtmp, event.size);  // send data 
                    break;
                case UART_FIFO_OVF:                 //  Hardware detected  FIFO  Overflow event  
                    ESP_LOGI(TAG, "hw fifo overflow");
                    // If fifo Overflow occurs , You should consider adding traffic control to your application .
                    //ISR It has been reset rx FIFO, for example , Let's refresh directly rx Buffer to read more data .
                    uart_flush_input(EX_UART_NUM);  // Clear input buffer , Discard all data in the ring buffer 
                    xQueueReset(uart0_queue);       // Reset a queue to its original empty state . The return value is now obsolete , And always set to pdPASS.
                    break;
                case UART_BUFFER_FULL:              //UART RX  Buffer full event 
                    ESP_LOGI(TAG, "ring buffer full");
                    //  If the buffer is full , You should consider increasing your buffer size 
                    //  for instance , Let's refresh directly here  rx  buffer , To read more data .uart_flush_input(EX_UART_NUM);
                    xQueueReset(uart0_queue);       // Reset a queue to its original empty state 
                    break;
                case UART_BREAK:                    //UART  Interruptions 
                    ESP_LOGI(TAG, "uart rx break");
                    break;
                case UART_PARITY_ERR:               //UART Parity error event 
                    ESP_LOGI(TAG, "uart parity error");
                    break;
                case UART_FRAME_ERR:                //UART  Frame error event 
                    ESP_LOGI(TAG, "uart frame error");
                    break;
                case UART_PATTERN_DET:              //UART  Enter the style detection event 
                    uart_get_buffered_data_len(EX_UART_NUM, &buffered_size);    //UART obtain RX The length of data cached in the ring buffer 
                    int pos = uart_pattern_pop_pos(EX_UART_NUM);                // Returns the most recently detected pattern position in the buffer 
                    ESP_LOGI(TAG, "[UART PATTERN DETECTED] pos: %d, buffered size: %d", pos, buffered_size);
                    if (pos == -1) {
    
                        // There used to be a UART_PATTERN_DET event , But the mode location queue is full , So it can't 
                        // Record location . We should set a larger queue size .
                        // for example , Let's refresh directly rx buffer .
                        uart_flush_input(EX_UART_NUM);  // Clear input buffer , Discard all data in the ring buffer  
                    } else {
    
                        uart_read_bytes(EX_UART_NUM, dtmp, pos, 100 / portTICK_PERIOD_MS);              // Reading data 
                        uint8_t pat[PATTERN_CHR_NUM + 1];                   
                        memset(pat, 0, sizeof(pat));    // Clear cache  
                        uart_read_bytes(EX_UART_NUM, pat, PATTERN_CHR_NUM, 100 / portTICK_PERIOD_MS);   // Reading data 
                        ESP_LOGI(TAG, "read data: %s", dtmp);
                        ESP_LOGI(TAG, "read pat : %s", pat);
                    }
                    break;
                default:                            // other 
                    ESP_LOGI(TAG, "uart event type: %d", event.type);
                    break;
            }
        }
    }
    free(dtmp);                                     // Free memory 
    dtmp = NULL;                                    // Clear memory pointer 
    vTaskDelete(NULL);                              // Delete task 
}

void app_main(void)
{
    
    esp_log_level_set(TAG, ESP_LOG_INFO);   // Set up ESP32 log Print level 

    // Configure parameters of an UART driver,  Configure serial driver function 
    // communication pins and install the driver  Communication pin and install driver 
    uart_config_t uart_config = {
    
        .baud_rate = 115200,                        // set baud rate 
        .data_bits = UART_DATA_8_BITS,              // set data bit 
        .parity = UART_PARITY_DISABLE,              // Set parity   Do not enable verification 
        .stop_bits = UART_STOP_BITS_1,              // A stop bit 
        .flow_ctrl = UART_HW_FLOWCTRL_DISABLE,      // Hardware flow control is not enabled 
        .source_clk = UART_SCLK_APB,                // The choice of clock source 
    };
    //Install UART driver, and get the queue. // Install serial driver   Serial channel   receive buf  send out buf  Event queue   Flag of allocation interruption 
    uart_driver_install(EX_UART_NUM, BUF_SIZE * 2, BUF_SIZE * 2, 20, &uart0_queue, 0);
    uart_param_config(EX_UART_NUM, &uart_config);   // Serial port parameter configuration 

    //Set UART log level
    esp_log_level_set(TAG, ESP_LOG_INFO);           // Set up ESP32 log Print level 
    //Set UART pins (using UART0 default pins ie no changes.) // Set the serial port pin   Serial number   Send pin   Receive pin  rts Pin  cts Pin 
    uart_set_pin(EX_UART_NUM, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);

    //Set uart pattern detect function. // Set the serial port parameter self-test function 
    uart_enable_pattern_det_baud_intr(EX_UART_NUM, '+', PATTERN_CHR_NUM, 9, 0, 0);
    //Reset the pattern queue length to record at most 20 pattern positions.
    uart_pattern_queue_reset(EX_UART_NUM, 20);      // Reset mode queue length , Maximum records 20 Two mode positions .

    //Create a task to handler UART event from ISR // Create a task to handle ISR Medium UART event 
    xTaskCreate(uart_event_task, "uart_event_task", 2048, NULL, 12, NULL);
}

Four 、 Serial port experimental demonstration results

 Insert picture description here

5、 ... and 、ESP32 Serial port function API

5.1、uart_types.h The contents of the document API

  uart_types.h The content in the file basically realizes the setting structure of some serial port protocols

// UART Port number , The value is UART_NUM_0 ~ (UART_NUM_MAX -1).
typedef int  uart_port_t;

// UART Mode selection 
typedef enum {
    
    UART_MODE_UART = 0x00,                     /*!< mode: Ordinary UART Pattern */
    UART_MODE_RS485_HALF_DUPLEX = 0x01,        /*!< mode: from RTS Pin controlled half duplex RS485 UART Pattern */
    UART_MODE_IRDA = 0x02,                     /*!< mode:IRDA UART Pattern */
    UART_MODE_RS485_COLLISION_DETECT = 0x03,   /*!< mode:RS485 collision detection UART Pattern ( For testing purposes )*/
    uart_mod_rs485_app_ctrl = 0x04,            /*!< mode: Application control RS485 UART Pattern ( For testing purposes )*/
} uart_mode_t;

//UART Word length constant 
typedef enum {
    
    UART_DATA_5_BITS = 0x0,    /*!< 5 Byte length  */
    UART_DATA_6_BITS = 0x1,    /*!< 6 Byte length  */
    UART_DATA_7_BITS = 0x2,    /*!< 7 Byte length  */
    UART_DATA_8_BITS = 0x3,    /*!< 8 Byte length  */
    UART_DATA_BITS_MAX = 0x4,
} uart_word_length_t;

//UART Stop digits 
typedef enum {
    
    UART_STOP_BITS_1   = 0x1,   /*!< 1 Byte stop bit  */
    UART_STOP_BITS_1_5 = 0x2,   /*!< 1.5 Byte stop bit  */
    UART_STOP_BITS_2   = 0x3,   /*!< 2 Byte stop bit  */
    UART_STOP_BITS_MAX = 0x4,
} uart_stop_bits_t;

//UART Parity constant 
typedef enum {
    
    UART_PARITY_DISABLE = 0x0,  /*!< Ban UART Parity check */
    UART_PARITY_EVEN    = 0x2,  /*!< Enable UART Even check */
    UART_PARITY_ODD     = 0x3    /*!< Enable UART Parity check */
} uart_parity_t;

//UART Hardware flow control mode 
typedef enum {
    
    UART_HW_FLOWCTRL_DISABLE = 0x0,/*!< Disable hardware flow control */
    UART_HW_FLOWCTRL_RTS = 0x1,    /*!< Enable RX Hardware flow control (rts)*/
    UART_HW_FLOWCTRL_CTS = 0x2,    /*!<enable TX Hardware flow control (cts)*/
    UART_HW_FLOWCTRL_CTS_RTS = 0x3,/*!< Enable hardware flow control */
    UART_HW_FLOWCTRL_MAX = 0 x4,
} uart_hw_flowcontrol_t;

//UART Signal bitmap 
typedef enum {
    
    Uart_signal_inv_disable = 0,           /*!< Ban UART Signal inversion */
    UART_SIGNAL_IRDA_TX_INV = (0x1 << 0),  /*!< back UART irda_tx The signal */
    UART_SIGNAL_IRDA_RX_INV = (0x1 << 1),  /*!< The inverse UART irda_rx The signal */
    UART_SIGNAL_RXD_INV = (0x1 << 2),      /*!< The inverse UART rxd The signal */
    UART_SIGNAL_CTS_INV = (0x1 << 3),      /*!< reverse UART cts The signal */
    UART_SIGNAL_DSR_INV = (0x1 << 4),      /*!< reverse UART dsr The signal */
    UART_SIGNAL_TXD_INV = (0x1 << 5),      /*!< The inverse UART txd The signal */
    UART_SIGNAL_RTS_INV = (0x1 << 6),      /*!< reverse UART rts The signal */
    UART_SIGNAL_DTR_INV = (0x1 << 7),      /*!< reverse UART dtr The signal */
} uart_signal_inv_t;

//UART Source clock 
typedef enum {
    
    UART_SCLK_APB = 0x0,       /*!< come from APB Of UART Source clock */
#if SOC_UART_SUPPORT_RTC_CLK
    UART_SCLK_RTC = 0x1,       /*!< UART The source clock comes from RTC*/
# endif
#if SOC_UART_SUPPORT_XTAL_CLK
    UART_SCLK_XTAL = 0x2,      /*!< UART The source clock comes from XTAL*/
# endif
#if SOC_UART_SUPPORT_REF_TICK
    UART_SCLK_REF_TICK = 0x3,  /*!< UART The source clock comes from REF_TICK*/
# endif
} uart_sclk_t;

/* * @brief  A serial port AT Command character configuration parameters  *  Note that this function may be different on different chips . Please refer to... When configuring TRM. */
typedef struct {
    
    uint8_t  cmd_char;      /* !< UART AT Configure command parameters  */
    uint8_t  char_num;      /* !< UART AT Command character repeat number  */
    uint32_t gap_tout;      /* !< AT Interval between command characters ( Baud rate ) */
    uint32_t pre_idle;      /* !<  Not AT Characters and the first AT Idle time between characters ( Baud rate ) */
    uint32_t post_idle;     /* !<  the last one AT Characters and none AT Idle time between characters ( Baud rate ) */
} uart_at_cmd_t;

/** * @brief UART Software flow control configuration parameters  */
typedef struct {
    
    uint8_t xon_char;       /* !< Xon Flow control character */
    uint8_t xoff_char;      /* !< Xoff Flow control character */
    uint8_t xon_thrd;       /* !< If software flow control is enabled , also rxfifo The amount of data in is less than xon_thrd, Send a xon_char */
    uint8_t xoff_thrd;      /* !< If software flow control is enabled , also rxfifo The amount of data in xoff_thrd, Send a xoff_char */
} uart_sw_flowctrl_t;

/** * @brief uart_param_config Functional UART Configuration parameters  */
typedef struct {
    
    int  baud_rate;                 /* !< UART Baud rate */
    uart_word_length_t data_bits;   /* !< UART Byte size */
    uart_parity_t parity;           /* !< UART Check mode */
    uart_stop_bits_t stop_bits;     /* !< UART Stop bit */
    uart_hw_flowcontrol_t flow_ctrl;/* !< UART HW Flow control mode (cts/rts)*/
    uint8_t rx_flow_ctrl_thresh;    /* !< UART HW RTS threshold */
    union{
    
        uart_sclk_t source_clk;     /* !< UART Source clock selection */
        bool use_ref_tick __attribute__((deprecated));  /* ! Deprecated method to select ref tick clock source, take source_clk Change the field to */
    };
} uart_config_t;

5.2、 stay uart.h The contents of the document API

   stay uart.h There is more in the file , Mainly ESP32 The architecture of the configuration parameters of the serial port, as well as the initialization function and configuration function , It also includes parameters and functions such as serial port events API. reminder : You can give these API Copy to text editor , for example Vscode in , Then you can quickly find and locate the function and the meaning of function parameters .

// Effective UART Port number 
#define UART_NUM_0 (0) /*!< UART port 0 */
#define UART_NUM_1 (1) /*!< UART port 1 */
#if SOC_UART_NUM > 2
#define UART_NUM_2 (2) /*!< UART port 2 */
# endif
#define UART_NUM_MAX (SOC_UART_NUM) /*!< UART port max */

/* @brief When calling ' uart_set_pin ', instead of GPIO number, ' UART_PIN_NO_CHANGE ' * A pin that holds the current assignment can be provided .*/
#define UART_PIN_NO_CHANGE (1)

SOC_UART_FIFO_LEN       //< UART  Hardware FIFO The length of 
SOC_UART_BITRATE_MAX    //< Maximum configurable bit rate 

//UART Interrupt configuration parameters uart_intr_config function 
typedef struct {
    
    uint32_t intr_enable_mask;          /* !< UART Interrupt enable mask , choice uart_xxxx_int _ena_reg (i) Under the UART_XXXX_int _ENA_M, Join bit or operator */
    uint8_t rx_timeout_thresh;          /* !< UART Timeout interrupt threshold ( Company : Time to send a byte )*/
    uint8_t txfifo_empty_intr_thresh;   /* !< UART TX Air break threshold .*/
    uint8_t rxfifo_full_thresh;         /* !< UART RX Full interrupt threshold .*/
} uart_intr_config_t;

//UART The event type is used in the circular buffer 
typedef enum {
    
    UART_DATA ,                         /*!< UART Data events */
    UART_BREAK ,                        /*!< UART Interruptions */
    UART_BUFFER_FULL ,                  /*!< UART RX Buffer full event */
    UART_FIFO_OVF ,                     /*!< UART FIFO Overflow event */
    UART_FRAME_ERR ,                    /*!< UART RX Frame error event */
    UART_PARITY_ERR ,                   /*!< UART RX Parity Events */
    UART_DATA_BREAK ,                   /*!< UART TX Data and interrupt events */
    UART_PATTERN_DET ,                  /*!<  detected UART Pattern */
    UART_EVENT_MAX ,                    /*!< UART Maximum event index */
} uart_event_type_t;            

// The event structure is used for UART Event queue 
typedef struct {
    
    uart_event_type_t type; /* !< UART Event type */
    size_t size;            /* !< UART_DATA The event UART data size */
    bool timeout_flag;      /* !< UART Data reading timeout flag UART_DATA event ( In the configuration RX TOUT No new data was received during the period )*/
                            /* !< If the event is caused by FIFO-full Caused by interruption , Then there will be no event with timeout flag before the next byte arrives */
} uart_event_t;

typedef intr_handle_t uart_isr_handle_t;

/* * @brief install UART Driver and set UART For default configuration . * UART ISR The processor will be attached to the same... Where this function runs CPU At the core . * Rx_buffer_size Should be greater than UART_FIFO_LEN.Tx_buffer_size Should be zero or greater than UART_FIFO_LEN. * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param rx_buffer_size UART RX Ring buffer size . * @param tx_buffer_size UART TX Ring buffer size . *  If set to 0, The driver will not use TX buffer ,TX Function will block the task , Until all the data is sent out . * @param queue_size UART Event queue size / depth . * @param uart_queue UART Event queue handle . Once the successful , A new queue handle will be written here to provide  *  visit UART event . If set to NULL, The driver will not use the event queue . * @param intr_alloc_flags Flag used to assign interrupts . One or more (ORred) * ESP_intr_FLAG_ * value . For more information, see esp_intr_alloc.h. There's no setup here ESP_intr_FLAG_IRAM * ( Driver's ISR The handler is not in IRAM in ) * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_driver_install(uart_port_t uart_num, int  rx_buffer_size, int  tx_buffer_size, int  queue_size, QueueHandle_t* uart_queue, int  intr_alloc_flags);

/* * @brief uninstall UART drive . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_driver_delete (uart_port_t uart_num);

/** * @brief Check whether the drive is installed  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - The real driver is installed  * - The wrong driver is not installed  */
bool uart_is_driver_installed (uart_port_t uart_num);

/** *  Set up UART Data bits . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param data_bit UART Data bits  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_word_length(uart_port_t uart_num, uart_word_length_t data_bit);

/* *  obtain UART Data bit configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param data_bit receive UART Pointer to the data bit value . * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, result Will be put in (*data_bit) */
esp_err_t uart_get_word_length(uart_port_t uart_num, uart_word_length_t* data_bit);

/** *  obtain UART Data bit configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param data_bit receive UART Pointer to the data bit value . * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, result Will be put in (*data_bit) */
esp_err_t uart_get_word_length(uart_port_t uart_num, uart_word_length_t* data_bit);

/** *  Set up UART Stop bit . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param stop_bits UART Stop bit  * @return * - ESP_OK success  * - ESP_FAIL Failure  */
esp_err_t uart_set_stop_bits(uart_port_t uart_num, uart_stop_bits_t stop_bits);

/** *  obtain UART Stop bit configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param stop_bits Accept UART Pointer to stop bit value . * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, The result will be put into (*stop_bit) */
esp_err_t uart_get_stop_bits(uart_port_t uart_num, uart_stop_bits_t* stop_bits);

/** * @brief Set up UART Check mode . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param parity_mode uart Parity configuration enum * @return * - ESP_FAIL Parameter error  * - ESP_OK success  */
esp_err_t uart_set_parity(uart_port_t uart_num, uart_parity_t parity_mode);

/** *  obtain UART Parity mode configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param parity_mode Accept UART Pointer to parity mode value . * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, The result will be put into (*parity_mode) */
esp_err_t uart_get_parity(uart_port_t uart_num, uart_parity_t* parity_mode);

/** *  Set up UART Baud rate . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param baudrate UART Baud rate . * @return * - ESP_FAIL Parameter error  * - ESP_OK success  */
esp_err_t uart_set_baudrate(uart_port_t uart_num, uint32_t baudrate);

/** *  obtain UART Baud rate configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param baudrate Accept UART Pointer to baud rate value  * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, The results will be entered (*baudrate) */
esp_err_t uart_get_baudrate(uart_port_t uart_num, uint32_t* baudrate);

/** * @brief Set up UART Line reverse mode  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param inverse_mask Select the connection to be reversed . Use ' uart_signal_inv_t ' Of ORred Mask  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_line_inverse(uart_port_t uart_num, uint32_t inverse_mask);

/** * @brief Set hardware flow control . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param flow_ctrl Hardware flow control mode  * @param rx_thresh Hardware RX Flow control threshold (0 ~ UART_FIFO_LEN). *  Only when UART_HW_FLOWCTRL_RTS When setting ,rx_threshresh The value will be set . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_hw_flow_ctrl(uart_port_t uart_num, uart_hw_flowcontrol_t flow_ctrl, uint8_t rx_thresh);

/** * @brief Set software flow control . * @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2 * @param Turn the switch on or off  * @param rx_thresh_xon Low water mark  * @param rx_thresh_xoff High water level  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_sw_flow_ctrl(uart_port_t uart_num, bool enable, uint8_t rx_thresh_xon, uint8_t rx_thresh_xoff);

/** *  obtain UART Hardware flow control configuration . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param flow_ctrl Options for different flow control modes . * @return * - ESP_FAIL Parameter error  * - ESP_OK Success, The result will be put into (*flow_ctrl) */
esp_err_t uart_get_hw_flow_ctrl(uart_port_t uart_num, uart_hw_flowcontrol_t* flow_ctrl);

/** * @brief eliminate UART Interrupt state  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param clr_mask Bitmask of interrupt status to be cleared . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_clear_in t_status(uart_port_t uart_num, uint32_t clr_mask);

/** *  Set up UART Interrupt enable  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param enable_mask Enable bitmask . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_enable_intr_mask(uart_port_t uart_num, uint32_t enable_mask);

/* * @brief eliminate UART Interrupt enable bit  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param disable_mask Disable bitmask of bits . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_disable_intr_mask(uart_port_t uart_num, uint32_t disable_mask);

/* *  Enable UART RX interrupt (RX_FULL and RX_TIMEOUT interrupt ) * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_enable_rx_intr (uart_port_t uart_num);

/* *  close UART RX interrupt (RX_FULL and RX_TIMEOUT interrupt ) * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_disable_rx_intr (uart_port_t uart_num);

/* * @brief close UART TX interrupt (TXFIFO_EMPTY interrupt ) * @param uart_num UART Port number  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_disable_tx_intr (uart_port_t uart_num);

/*  open UART TX interrupt (TXFIFO_EMPTY interrupt ) * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param Enable 1: Enable ;0: Ban  * @param thresh TX Interrupt threshold ,0 ~ UART_FIFO_LEN * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_enable_tx_intr(uart_port_t uart_num, int  enable, int  thresh);

/* *  register UART Interrupt processor (ISR). * @note UART ISR The processor will be attached to the same... Where this function runs CPU At the core . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param fn Interrupt handling function . * @param Function of parameter handler  * @param intr_alloc_flags Flag used to assign interrupts . One or more (ORred) * ESP_intr_FLAG_ * value . For more information, see esp_intr_alloc.h. *  Returns a pointer to the handle . If the null, The interrupt handle will  *  Back here . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_isr_register(uart_port_t uart_num, void (*fn)(void*), void* arg, int  intr_alloc_flags, uart_isr_handle_t *handle);

/* *  Free of charge UART Interrupt handler registered uart_isr_register. Must be called in the same core  * uart_isr_register Called . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_isr_free (uart_port_t uart_num);

/* *  take UART Signals from peripherals are assigned to GPIO Pin  *  If UART Signal configuration GPIO Number matches one of them  * IOMUX The signal is this GPIO, The signal will be connected directly  *  adopt IOMUX. otherwise GPIO And the signal will pass through  * GPIO matrix . for example ESP32 conversation  * ' uart_set_pin(0,1,3, -1, -1) ' Be performed , because GPIO1 yes UART0 Of  *  default TX Pins and GPIO3 yes UART0 Default RX Pin , Both are  *  adopt IOMUX Separate connection U0TXD and U0RXD, Common bypass GPIO matrix . *  The check is performed on a per stitch basis . therefore , There may be  * RX Pin pass GPIO The matrix is bound to GPIO On , and TX Is bound.  *  adopt IOMUX Connect to GPIO. * @note Internal signals can be output to multiple GPIO plate . *  Only one input signal can be connected GPIO plate . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param tx_io_num UART TX Pin GPIO Number . * @param rx_io_num UART RX Pin GPIO Number . * @param rts_io_num UART RTS Pin GPIO Number . * @param cts_io_num UART CTS Pin GPIO Number . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_pin(uart_port_t uart_num, int  tx_io_num, int  rx_io_num, int  rts_io_num, int  cts_io_num);

/* * @brief Manual settings UART RTS Pin level . *  Be careful UART Must be configured to disable hardware flow control . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param 1 level :RTS Low output ( active );0: RTS High output ( block ) * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_rts(uart_port_t uart_num, int  level);

/* *  Manual settings UART DTR Pin level . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param level 1: DTR Low output ;0: DTR High output  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_dtr(uart_port_t uart_num, int  level);

/* * @brief Set up UART After idle interval tx FIFO It's empty.  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param idle_num tx FIFO The idle interval after is empty ( Company : The time required to send a bit ) *  At the current baud rate ) * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_set_tx_idle_num(uart_port_t uart_num, uint 16_t idle_num);

/* * @brief UART Configuration parameters . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param uart_config UART Parameter setting  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_param_config(uart_port_t uart_num, const uart_config_t *uart_config)

/** *  To configure UART interrupt . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param intr_conf UART Interrupt settings  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_intr_config(uart_port_t uart_num, const uart_intr_config_t *intr_conf);

/* * @brief Wait until UART TX FIFO It's empty. . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param ticks_to_wait Timeout time , With RTOS Timing and counting  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  * - ESP_ERR_TIMEOUT Timeout time  */
esp_err_t uart_wait_tx_done(uart_port_t uart_num, TickType_t ticks_to_wait);

/* *  Send data from a given buffer and length to UART port . *  This function will not wait for enough space in TX FIFO. It will populate the available TX FIFO, And in FIFO Return when full . * @ Note that this function should only be used in UART TX Use when buffer is not enabled . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param Buffer data buffer address  * @param len Length of data sent  * @return * -(-1) Parameter error  * - OTHERS(>=0) Send to TX FIFO Bytes of  */
int  uart_tx_chars(uart_port_t uart_num, const char* buffer, uint32_t len);

/** *  Send data from a given buffer and length to UART port , *  If UART Driver parameters tx_buffer_size Set to zero : *  This function will not return , Until all the data has been sent out , Or at least push TX FIFO. *  otherwise , If 'tx_buffer_size' > 0, This function copies all the data returned to tx Ring buffer , *  then UART ISR Gradually move the data from the ring buffer to TX FIFO. * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param SRC Data buffer address  * @param size Length of data sent  * @return * -(-1) Parameter error  * - OTHERS(>=0) Send to TX FIFO Bytes of  */
int  uart_write_bytes(uart_port_t uart_num, const void* src, size_t size);

/** *  Send data from a given buffer and length to UART port , *  If UART Driver parameters tx_buffer_size Set to zero : *  This function will not return , Until all data and interrupt signals have been sent . *  After all data is sent , Send interrupt signal . *  otherwise , If 'tx_buffer_size' > 0, This function copies all the data returned to tx Ring buffer , *  then UART ISR Gradually move the data from the ring buffer to TX FIFO. *  After all data is sent , Send interrupt signal . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param SRC Data buffer address  * @param size Length of data sent  * @param brk_len Interrupt signal duration ( Company : The time required to send a bit at the current baud rate ) * @return * -(-1) Parameter error  * - OTHERS(>=0) Send to TX FIFO Bytes of  */
int  uart_write_bytes_with_break(uart_port_t uart_num, const void* src, size_t size, int  brk_len);

/* * @brief UART from UART buffer Read bytes in  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param buf Pointer to buffer . * @param length Data length  * @param ticks_to_wait Timeout time , With RTOS timing  * @return * -(-1) error  * - OTHERS(>=0) from UART FIFO Number of bytes read  */
int  uart_read_bytes(uart_port_t uart_num, void* buf, uint32_t length, TickType_t ticks_to_wait);

/* * @brief uart_flush_input Another name for . * UART Ring buffer flushing . This will discard UART RX All data in the buffer . * @note Not waiting for data to be sent , Clear this function UART rx buffer . *  In order to send all the data in tx FIFO, We can use uart_wait_tx_done function . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_flush (uart_port_t uart_num);

/* * @brief Clear input buffer , Discard all data in the ring buffer . *  In order to be in tx FIFO Send all data in , We can use uart_wait_tx_done function . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_flush_input (uart_port_t uart_num);

/* * @brief UART obtain RX The length of data cached in the ring buffer  * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param size size_t The pointer to , The length used to accept cached data  * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_get_buffered_data_len(uart_port_t uart_num, size_t* size);

/* * @brief UART Disable the mode detection function . *  Designed for applications such as “AT command ”. *  When the hardware detects a series of identical characters , Will trigger an interrupt . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_disable_pattern_det_intr (uart_port_t uart_num);

#if CONFIG_IDF_TARGET_ESP32
/* * @brief UART Enable the mode detection function . *  Designed for applications such as “AT command ”. *  When the hardware detects a series of identical characters , Will trigger an interrupt . * @ Note that this function only applies to esp32. This function is deprecated , Please use  * uart_enable_pattern_det_baud_intr Instead of . * @param uart_num UART Port number . * @param pattern_chr Pattern characters . * @param chr_num Number of characters ,8 A value . * @param chr_tout The interval between each pattern character timed out ,24 A value , The unit is APB (80Mhz) Clock cycle . *  When the duration is less than this value , It will not accept this data as at_cmd character . * @param post_idle Idle time after the last mode character ,24 A value , The unit is APB (80Mhz) Clock cycle . *  When the duration is less than this value , It will not accept the previous data as the last at_cmd character  * @param pre_idle Idle time before the first mode character ,24 A value , The unit is APB (80Mhz) Clock cycle . *  When the duration is less than this value , It will not accept this data as the first at_cmd character . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_enable_pattern_det_intr(uart_port_t uart_num, char pattern_chr, uint8_t chr_num, int  chr_tout, int  post_idle, int  pre_idle) __attribute__((deprecated));
# endif

/* * @brief UART Enable the mode detection function . *  Designed for applications such as “AT command ”. *  When the hardware detects a series of identical characters , Will trigger an interrupt . * @param uart_num UART Port number . * @param pattern_chr Pattern characters . * @param chr_num Number of characters ,8 A value . * @param chr_tout The interval timeout between each pattern character ,16 A value , The unit is the baud rate cycle you configured . *  When the duration is greater than this value , It will not accept this data as at_cmd character . * @param post_idle Idle time after the last mode character ,16 A value , The unit is the baud rate cycle you configured . *  When the duration is less than this value , It will not accept the previous data as the last at_cmd character  * @param pre_idle Idle time before the first mode character ,16 A value , The unit is the baud rate cycle you configured . *  When the duration is less than this value , It will not accept this data as the first at_cmd character . * @return * - ESP_OK success  * - ESP_FAIL Parameter error  */
esp_err_t uart_enable_pattern_det_baud_intr(uart_port_t uart_num, char pattern_chr, uint8_t chr_num, int  chr_tout, int  post_idle, int  pre_idle);

/* *  Returns the most recently detected pattern position in the buffer . *  The position of the detected pattern is saved in a queue , *  This function will exit the first mode position , And move the pointer to the next mode position . *  If RX The buffer is full and flow control is not enabled , *  Due to overflow , The detected pattern may not be available in rx Found... In buffer . *  following api The mode location information will be modified : * uart_flush_input, uart_read_bytes, uart_driver_delete, uart_pop_pattern_pos *  Make sure that the mode queue and rx Atomic access to the data buffer is the responsibility of the application  *  When using pattern detection features . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * -(-1) The mode with the current index or parameter error was not found  * - Other modes are located in rx buffer . */
int  uart_pattern_pop_pos (uart_port_t uart_num);

/* *  Returns the most recently detected pattern position in the buffer . *  The position of the detected pattern is saved in a queue , *  This function does nothing to the queue . *  If RX The buffer is full and flow control is not enabled , *  Due to overflow , The detected pattern may not be available in rx Found... In buffer . *  following api The mode location information will be modified : * uart_flush_input, uart_read_bytes, uart_driver_delete, uart_pop_pattern_pos *  Make sure that the mode queue and rx Atomic access to the data buffer is the responsibility of the application  *  When using pattern detection features . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @return * -(-1) The mode with the current index or parameter error was not found  * - Other modes are located in rx buffer . */
int  uart_pattern_get_pos (uart_port_t uart_num);

/* *  Allocate a new memory of a given length to save rx Mode position detected in buffer . * @param uart_num UART Port number , The maximum port number is (UART_NUM_MAX -1). * @param queue_length The maximum queue length of the detected pattern . *  If the queue length is not large enough , Some mode locations may be lost . *  Set this value to the maximum number of data buffer modes that can be saved at the same time . * @return * - ESP_ERR_NO_MEM Out of memory  * - Not installed ESP_ERR_INVALID_STATE The driver  * - ESP_FAIL Parameter error  * - ESP_OK success  */
esp_err_t uart_pattern_queue_reset(uart_port_t uart_num, int  queue_length);

/* * @brief UART Set the communication mode  * @note This function must be in the uart_driver_install() after , When the driver object is initialized, execute . * @param uart_num To configure Uart Number , The maximum port number is (UART_NUM_MAX -1). * @param mode UART UART Mode setting  * @return * - ESP_OK success  * - ESP_ERR_INVALID_ARG Parameter error  */
esp_err_t uart_set_mode(uart_port_t uart_num, uart_mode_t mode);

/* * @brief Set up RX fifo Full of uart threshold  * @note If the application uses a higher baud rate , It is the observation byte  *  In hardware RX fifo Be overwritten , This threshold can then be reduced  * @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2 * @param threshold RX fifo Threshold of full interrupt  * @return * - ESP_OK success  * - ESP_ERR_INVALID_ARG Parameter error  * - Not installed ESP_ERR_INVALID_STATE The driver  */
esp_err_t uart_set_rx_full_threshold(uart_port_t uart_num, int  threshold);

/* * @brief Set up uart The threshold is empty fifo * @param uart_num UART_NUM_0, UART_NUM_1 or UART_NUM_2 * @param threshold TX fifo The threshold value of air interruption  * @return * - ESP_OK success  * - ESP_ERR_INVALID_ARG Parameter error  * - Not installed ESP_ERR_INVALID_STATE The driver  */
esp_err_t uart_set_tx_empty_threshold(uart_port_t uart_num, int  threshold);

/** * @brief UART by TOUT Property setting threshold timeout  * @param uart_num To configure Uart Number , The maximum port number is (UART_NUM_MAX -1). * @param tout_thresh With uart The symbol period defines the timeout threshold . The maximum value of the threshold is 126. * tout_thresh = 1, Defined TOUT Interrupt timeout , Equal to the current baud rate, the next symbol (~11 position ) The transmission time of . *  When time passes, it will trigger UART_RXFIFO_TOUT_int  interrupt . If tout_thresh == 0, *  Ban TOUT function . * @return * - ESP_OK success  * - ESP_ERR_INVALID_ARG Parameter error  * - Not installed ESP_ERR_INVALID_STATE The driver  */
esp_err_t uart_set_rx_timeout(uart_port_t uart_num, const uint8_t tout_thresh);

/** * @brief by RS485 Return to collision detection mode  *  The function returns a collision detection flag collision_flag Variable pointed to . * *collision_flag = true, If a collision is detected , Otherwise it is equal to false. *  This function should be executed when the actual transfer is completed ( stay uart_write_bytes() after ). * @param uart_num The maximum port number configured is (UART_NUM_MAX -1). * @param collision_flag bool Pointer to type variable , Returns the collision flag . * @return * - ESP_OK success  * - ESP_ERR_INVALID_ARG Parameter error  */
esp_err_t uart_get_collision_flag(uart_port_t uart_num, bool* collision_flag);

/** *  Set up RX Number of pin signal edges , Used for light sleep and wake-up  * UART It can be used to wake up the system from mild sleep . This feature is very useful  *  Through counting RX The number of positive sides on the pin , And compare the count with  *  threshold . When the count exceeds the threshold , The system will wake up  *  Just sleep . Provide threshold setting function . *  Stop bit and parity bit ( If enabled ) It also affects the number of edges . *  for example ,ASCII code 97 The letter of “a” Encoded on the network as 0100001101 * ( And 8n1 To configure ), Including start and stop bits . This sequence has 3 individual  *  Positive edge ( from 0 The transition to 1). therefore , arousal system  *  When 'a' When sent , Set up wakeup_threshold=3. *  The character that triggered the wake-up was not UART receive ( That is, it cannot  *  from UART FIFO get ). According to the baud rate , A few characters  *  It will not be accepted after . Please note that , When the chip enters and exits  *  Light sleep mode ,APB The frequency will change . Make sure UART Yes  *  Always correct baud rate , choice REF_TICK As UART Clock source , *  take uart_config_t Medium use_ref_tick Field set to true. * @note stay ESP32 in , The wake-up signal can only pass through IO_MUX( namely IO_MUX) Input . * GPIO3 It should be configured as function_1 Wake up UART0, * GPIO9 It should be configured as function_5 Wake up UART1), UART2 *  Light sleep wake-up function is not supported . * @param uart_num UART Number , The maximum port number is (UART_NUM_MAX -1). * @param wakeup_threshold RX Number of edges , Wake up for light sleep , The value is 3 ..0 x3ff. * @return * - ESP_OK It means success  * - uart_num Incorrect or wakeup_threshold When incorrect, it is ESP_ERR_INVALID_ARG *  stay [3,0x3ff] Beyond the range . */
esp_err_t uart_set_wakeup_threshold(uart_port_t uart_num, int  wakeup_threshold);

/** *  obtain RX The number of pin signal edges is light sleep wake-up . *  About UART See for an explanation of uart_set_wakeup_threshold Description of  *  Wake up function . * @param uart_num UART Number , The maximum port number is (UART_NUM_MAX -1). * @param[out] out_wakeup_threshold Output , Set to wakeup The current value of the  *  Given UART The threshold of . * @return * - ESP_OK It means success  * - If out_wakeup_threshold by NULL, be ESP_ERR_INVALID_ARG */
esp_err_t uart_get_wakeup_threshold(uart_port_t uart_num, int * out_wakeup_threshold);

/** * @brief Wait until UART tx Memory is empty and the last character is sent ok( Polling mode ). * @param uart_num UART Number  * * @return * - ESP_OK It means success  * - ESP_ERR_INVALID_ARG Parameter error  * - Not installed ESP_FAIL drive  */
esp_err_t uart_wait_tx_idle_polling (uart_port_t uart_num);

/** *  To configure TX The signal goes back to RX modular , For testing purposes only . * @param uart_num UART Number  * @param loop_back_en Set to true To enable the loopback function , Otherwise set to false. * * @return * - ESP_OK It means success  * - ESP_ERR_INVALID_ARG Parameter error  * - Not installed ESP_FAIL drive  */
esp_err_t uart_set_loop_back(uart_port_t uart_num, bool loop_back_en);

/** *  To configure UART RX Timeout interrupt behavior . *  When always_rx_timeout by true when , Even if FIFO A timeout interrupt will also be triggered when it is full . *  This function can cause additional timeout interrupts to trigger sending only timeout Events . *  Only if you want to ensure that timeout interrupts always occur after the byte stream , To call this function . * @param uart_num UART Number  * @param always_rx_timeout_en Set to false Enables the default behavior for timeout interrupts , * Set to true Always trigger timeout interrupt . */
Void uart_set_always_rx_timeout(uart_port_t uart_num, bool always_rx_timeout_en);

版权声明
本文为[Please call me Xiao Peng]所创,转载请带上原文链接,感谢
https://yzsam.com/2022/04/202204210609449964.html