Serial (UART)

About

The Serial (UART - Universal Asynchronous Receiver-Transmitter) peripheral provides asynchronous serial communication, allowing the ESP32 to communicate with other devices such as computers, sensors, displays, and other microcontrollers.

UART is a simple, two-wire communication protocol that uses a TX (transmit) and RX (receive) line for full-duplex communication. The ESP32 Arduino implementation provides a HardwareSerial class that is compatible with the standard Arduino Serial API, with additional features for advanced use cases.

Key Features:

  • Full-duplex communication: Simultaneous transmission and reception

  • Configurable baud rates: From 300 to 5,000,000+ baud

  • Multiple data formats: Configurable data bits, parity, and stop bits

  • Hardware flow control: Support for RTS/CTS signals

  • RS485 support: Half-duplex RS485 communication mode

  • Low-power UART: Some SoCs support LP (Low-Power) UART for ultra-low power applications

  • Baud rate detection: Automatic baud rate detection (ESP32, ESP32-S2 only)

  • Event callbacks: Receive and error event callbacks

  • Configurable buffers: Adjustable RX and TX buffer sizes

Note

In case that both pins, RX and TX are detached from UART, the driver will be stopped. Detaching may occur when, for instance, starting another peripheral using RX and TX pins, such as Wire.begin(RX0, TX0).

UART Availability

The number of UART peripherals available varies by ESP32 SoC:

ESP32 SoC

HP UARTs

LP UARTs

ESP32

3

0

ESP32-S2

2

0

ESP32-S3

3

0

ESP32-C3

2

0

ESP32-C5

2

1

ESP32-C6

2

1

ESP32-H2

2

0

ESP32-P4

5

1

Note: * HP (High-Performance) UARTs are the standard UART peripherals * LP (Low-Power) UARTs are available on some SoCs for ultra-low power applications * UART0 is typically used for programming and debug output (Serial Monitor) * Additional UARTs (Serial1, Serial2, etc.) are available for general-purpose communication, including LP UARTs when available. The ESP32 Arduino Core automatically creates HardwareSerial objects for all available UARTs:

  • Serial0 (or Serial) - UART0 (HP UART, typically used for programming and debug output)

  • Serial1, Serial2, etc. - Additional HP UARTs (numbered sequentially)

  • Additional Serial objects - LP UARTs, when available (numbered after HP UARTs)

Example: The ESP32-C6 has 2 HP UARTs and 1 LP UART. The Arduino Core creates Serial0 and Serial1 (HP UARTs) plus Serial2 (LP UART) HardwareSerial objects.

Important: LP UARTs can be used as regular UART ports, but they have fixed GPIO pins for RX, TX, CTS, and RTS. It is not possible to change the pins for LP UARTs using setPins().

Arduino-ESP32 Serial API

begin

Initializes the Serial port with the specified baud rate and configuration.

void begin(unsigned long baud, uint32_t config = SERIAL_8N1, int8_t rxPin = -1, int8_t txPin = -1, bool invert = false, unsigned long timeout_ms = 20000UL, uint8_t rxfifo_full_thrhd = 120);
  • baud - Baud rate (bits per second). Common values: 9600, 115200, 230400, etc.

    Special value: 0 enables baud rate detection (ESP32, ESP32-S2 only). The function will attempt to detect the baud rate for up to timeout_ms milliseconds. See the Baud Rate Detection Example for usage details.

  • config - Serial configuration (data bits, parity, stop bits):

    • SERIAL_8N1 - 8 data bits, no parity, 1 stop bit (default)

    • SERIAL_8N2 - 8 data bits, no parity, 2 stop bits

    • SERIAL_8E1 - 8 data bits, even parity, 1 stop bit

    • SERIAL_8E2 - 8 data bits, even parity, 2 stop bits

    • SERIAL_8O1 - 8 data bits, odd parity, 1 stop bit

    • SERIAL_8O2 - 8 data bits, odd parity, 2 stop bits

    • SERIAL_7N1, SERIAL_7N2, SERIAL_7E1, SERIAL_7E2, SERIAL_7O1, SERIAL_7O2 - 7 data bits variants

    • SERIAL_6N1, SERIAL_6N2, SERIAL_6E1, SERIAL_6E2, SERIAL_6O1, SERIAL_6O2 - 6 data bits variants

    • SERIAL_5N1, SERIAL_5N2, SERIAL_5E1, SERIAL_5E2, SERIAL_5O1, SERIAL_5O2 - 5 data bits variants

  • rxPin - RX pin number. Use -1 to keep the default pin or current pin assignment.

  • txPin - TX pin number. Use -1 to keep the default pin or current pin assignment.

  • invert - If true, inverts the RX and TX signal polarity.

  • timeout_ms - Timeout in milliseconds for baud rate detection (when baud = 0). Default: 20000 ms (20 seconds).

  • rxfifo_full_thrhd - RX FIFO full threshold (1-127 bytes). When the FIFO reaches this threshold, data is copied to the RX buffer. Default: 120 bytes.

Example:

// Basic initialization with default pins
Serial.begin(115200);

// Initialize with custom pins
Serial1.begin(9600, SERIAL_8N1, 4, 5);

// Initialize with baud rate detection (ESP32, ESP32-S2 only)
Serial.begin(0, SERIAL_8N1, -1, -1, false, 20000);

end

Stops the Serial port and releases all resources.

void end(void);

This function disables the UART peripheral and frees all associated resources.

available

Returns the number of bytes available for reading from the Serial port.

int available(void);

Returns: The number of bytes available in the RX buffer, or 0 if no data is available.

Example:

if (Serial.available() > 0) {
    char data = Serial.read();
}

availableForWrite

Returns the number of bytes that can be written to the Serial port without blocking.

int availableForWrite(void);

Returns: The number of bytes that can be written to the TX buffer without blocking.

read

Reads a single byte from the Serial port.

int read(void);

Returns: The byte read (0-255), or -1 if no data is available.

Example:

int data = Serial.read();
if (data != -1) {
    Serial.printf("Received: %c\n", data);
}

read (buffer)

Reads multiple bytes from the Serial port into a buffer.

size_t read(uint8_t *buffer, size_t size);
size_t read(char *buffer, size_t size);
  • buffer - Pointer to the buffer where data will be stored

  • size - Maximum number of bytes to read

Returns: The number of bytes actually read.

Example:

uint8_t buffer[64];
size_t bytesRead = Serial.read(buffer, sizeof(buffer));
Serial.printf("Read %d bytes\n", bytesRead);

readBytes

Reads multiple bytes from the Serial port, blocking until the specified number of bytes is received or timeout occurs.

size_t readBytes(uint8_t *buffer, size_t length);
size_t readBytes(char *buffer, size_t length);
  • buffer - Pointer to the buffer where data will be stored

  • length - Number of bytes to read

Returns: The number of bytes actually read (may be less than length if timeout occurs).

Note: This function overrides Stream::readBytes() for better performance using ESP-IDF functions.

write

Writes data to the Serial port.

size_t write(uint8_t);
size_t write(const uint8_t *buffer, size_t size);
size_t write(const char *buffer, size_t size);
size_t write(const char *s);
size_t write(unsigned long n);
size_t write(long n);
size_t write(unsigned int n);
size_t write(int n);
  • Single byte: write(uint8_t) - Writes a single byte

  • Buffer: write(buffer, size) - Writes multiple bytes from a buffer

  • String: write(const char *s) - Writes a null-terminated string

  • Number: write(n) - Writes a number as a single byte

Returns: The number of bytes written.

Example:

Serial.write('A');
Serial.write("Hello");
Serial.write(buffer, 10);
Serial.write(65);  // Writes byte value 65

peek

Returns the next byte in the RX buffer without removing it.

int peek(void);

Returns: The next byte (0-255), or -1 if no data is available.

Note: Unlike read(), peek() does not remove the byte from the buffer.

flush

Waits for all data in the TX buffer to be transmitted.

void flush(void);
void flush(bool txOnly);
  • txOnly - If true, only flushes the TX buffer. If false (default), also clears the RX buffer.

Note: This function blocks until all data in the TX buffer has been sent.

baudRate

Returns the current baud rate of the Serial port.

uint32_t baudRate(void);

Returns: The configured baud rate in bits per second.

Note: When using baud rate detection (begin(0)), this function returns the detected baud rate, which may be slightly rounded (e.g., 115200 may return 115201).

updateBaudRate

Updates the baud rate of an already initialized Serial port.

void updateBaudRate(unsigned long baud);
  • baud - New baud rate

Note: This function can be called after begin() to change the baud rate without reinitializing the port.

setPins

Sets or changes the RX, TX, CTS, and RTS pins for the Serial port.

bool setPins(int8_t rxPin, int8_t txPin, int8_t ctsPin = -1, int8_t rtsPin = -1);
  • rxPin - RX pin number. Use -1 to keep current pin.

  • txPin - TX pin number. Use -1 to keep current pin.

  • ctsPin - CTS (Clear To Send) pin for hardware flow control. Use -1 to keep current pin or disable.

  • rtsPin - RTS (Request To Send) pin for hardware flow control. Use -1 to keep current pin or disable.

Returns: true if pins are set successfully, false otherwise.

Note: This function can be called before or after begin(). When pins are changed, the previous pins are automatically detached.

setRxBufferSize

Sets the size of the RX buffer.

size_t setRxBufferSize(size_t new_size);
  • new_size - New RX buffer size in bytes

Returns: The actual buffer size set, or 0 on error.

Note: This function must be called before begin() to take effect. Default RX buffer size is 256 bytes.

setTxBufferSize

Sets the size of the TX buffer.

size_t setTxBufferSize(size_t new_size);
  • new_size - New TX buffer size in bytes

Returns: The actual buffer size set, or 0 on error.

Note: This function must be called before begin() to take effect. Default TX buffer size is 0 (no buffering).

setRxTimeout

Sets the RX timeout threshold in UART symbol periods.

bool setRxTimeout(uint8_t symbols_timeout);
  • symbols_timeout - Timeout threshold in UART symbol periods. Setting 0 disables timeout-based callbacks.

    The timeout is calculated based on the current baud rate and serial configuration. For example:

    • For SERIAL_8N1 (10 bits per symbol), a timeout of 3 symbols at 9600 baud = 3 / (9600 / 10) = 3.125 ms

    • Maximum timeout is calculated automatically by ESP-IDF based on the serial configuration

Returns: true if timeout is set successfully, false otherwise.

Note: * When RX timeout occurs, the onReceive() callback is triggered * For ESP32 and ESP32-S2, when using REF_TICK clock source (baud rates ≤ 250000), RX timeout is limited to 1 symbol * To use higher RX timeout values on ESP32/ESP32-S2, set the clock source to APB using setClockSource(UART_CLK_SRC_APB) before begin()

setRxFIFOFull

Sets the RX FIFO full threshold that triggers data transfer from FIFO to RX buffer.

bool setRxFIFOFull(uint8_t fifoBytes);
  • fifoBytes - Number of bytes (1-127) that will trigger the FIFO full interrupt

    When the UART FIFO reaches this threshold, data is copied to the RX buffer and the onReceive() callback is triggered.

Returns: true if threshold is set successfully, false otherwise.

Note: * Lower values (e.g., 1) provide byte-by-byte reception but consume more CPU time * Higher values (e.g., 120) provide better performance but introduce latency * Default value depends on baud rate: 1 byte for ≤ 115200 baud, 120 bytes for > 115200 baud

onReceive

Sets a callback function that is called when data is received.

void onReceive(OnReceiveCb function, bool onlyOnTimeout = false);
  • function - Callback function to call when data is received. Use NULL to disable the callback.

  • onlyOnTimeout - If true, callback is only called on RX timeout. If false (default), callback is called on both FIFO full and RX timeout events.

Callback Signature:

typedef std::function<void(void)> OnReceiveCb;

Note: * When onlyOnTimeout = false, the callback is triggered when FIFO reaches the threshold (set by setRxFIFOFull()) or on RX timeout * When onlyOnTimeout = true, the callback is only triggered on RX timeout, ensuring all data in a stream is available at once * Using onlyOnTimeout = true may cause RX overflow if the RX buffer size is too small for the incoming data stream * The callback is executed in a separate task, allowing non-blocking data processing

Example:

void onReceiveCallback() {
    while (Serial1.available()) {
        char c = Serial1.read();
        Serial.print(c);
    }
}

void setup() {
    Serial1.begin(115200);
    Serial1.onReceive(onReceiveCallback);
}

onReceiveError

Sets a callback function that is called when a UART error occurs.

void onReceiveError(OnReceiveErrorCb function);
  • function - Callback function to call when an error occurs. Use NULL to disable the callback.

Callback Signature:

typedef std::function<void(hardwareSerial_error_t)> OnReceiveErrorCb;

Error Types:

  • UART_NO_ERROR - No error

  • UART_BREAK_ERROR - Break condition detected

  • UART_BUFFER_FULL_ERROR - RX buffer is full

  • UART_FIFO_OVF_ERROR - UART FIFO overflow

  • UART_FRAME_ERROR - Frame error (invalid stop bit)

  • UART_PARITY_ERROR - Parity error

Example:

void onErrorCallback(hardwareSerial_error_t error) {
    Serial.printf("UART Error: %d\n", error);
}

void setup() {
    Serial1.begin(115200);
    Serial1.onReceiveError(onErrorCallback);
}

eventQueueReset

Clears all events in the event queue (events that trigger onReceive() and onReceiveError()).

void eventQueueReset(void);

This function can be useful in some use cases where you want to clear pending events.

setHwFlowCtrlMode

Enables or disables hardware flow control using RTS and/or CTS pins.

bool setHwFlowCtrlMode(SerialHwFlowCtrl mode = UART_HW_FLOWCTRL_CTS_RTS, uint8_t threshold = 64);
  • mode - Hardware flow control mode:

    • 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 full hardware flow control (default)

  • threshold - Flow control threshold (default: 64, which is half of the FIFO length)

Returns: true if flow control mode is set successfully, false otherwise.

Note: CTS and RTS pins must be set using setPins() before enabling hardware flow control.

setMode

Sets the UART operating mode.

bool setMode(SerialMode mode);
  • mode - UART mode:

    • UART_MODE_UART (0x00) - Regular UART mode (default)

    • UART_MODE_RS485_HALF_DUPLEX (0x01) - Half-duplex RS485 mode (RTS pin controls transceiver)

    • UART_MODE_IRDA (0x02) - IRDA UART mode

    • UART_MODE_RS485_COLLISION_DETECT (0x03) - RS485 collision detection mode (for testing)

    • UART_MODE_RS485_APP_CTRL (0x04) - Application-controlled RS485 mode (for testing)

Returns: true if mode is set successfully, false otherwise.

Note: For RS485 half-duplex mode, the RTS pin must be configured using setPins() to control the transceiver.

setClockSource

Sets the UART clock source. Must be called before begin() to take effect.

bool setClockSource(SerialClkSrc clkSrc);
  • clkSrc - Clock source:

    • UART_CLK_SRC_DEFAULT - Default clock source (varies by SoC)

    • UART_CLK_SRC_APB - APB clock (ESP32, ESP32-S2, ESP32-C3, ESP32-S3)

    • UART_CLK_SRC_PLL - PLL clock (ESP32-C2, ESP32-C5, ESP32-C6, ESP32-C61, ESP32-H2, ESP32-P4)

    • UART_CLK_SRC_XTAL - XTAL clock (ESP32-C2, ESP32-C3, ESP32-C5, ESP32-C6, ESP32-C61, ESP32-H2, ESP32-S3, ESP32-P4)

    • UART_CLK_SRC_RTC - RTC clock (ESP32-C2, ESP32-C3, ESP32-C5, ESP32-C6, ESP32-C61, ESP32-H2, ESP32-S3, ESP32-P4)

    • UART_CLK_SRC_REF_TICK - REF_TICK clock (ESP32, ESP32-S2)

Note: * Clock source availability varies by SoC. * PLL frequency varies by SoC: ESP32-C2 (40 MHz), ESP32-H2 (48 MHz), ESP32-C5/C6/C61/P4 (80 MHz). * ESP32-C5, ESP32-C6, ESP32-C61, and ESP32-P4 have LP UART that uses only RTC_FAST or XTAL/2 as clock source. * For ESP32 and ESP32-S2, REF_TICK is used by default for baud rates ≤ 250000 to avoid baud rate changes when CPU frequency changes, but this limits RX timeout to 1 symbol.

Returns: true if clock source is set successfully, false otherwise.

setRxInvert

Enables or disables RX signal inversion.

bool setRxInvert(bool invert);
  • invert - If true, inverts the RX signal polarity

Returns: true if inversion is set successfully, false otherwise.

setTxInvert

Enables or disables TX signal inversion.

bool setTxInvert(bool invert);
  • invert - If true, inverts the TX signal polarity

Returns: true if inversion is set successfully, false otherwise.

setCtsInvert

Enables or disables CTS signal inversion.

bool setCtsInvert(bool invert);
  • invert - If true, inverts the CTS signal polarity

Returns: true if inversion is set successfully, false otherwise.

setRtsInvert

Enables or disables RTS signal inversion.

bool setRtsInvert(bool invert);
  • invert - If true, inverts the RTS signal polarity

Returns: true if inversion is set successfully, false otherwise.

setDebugOutput

Enables or disables debug output on this Serial port.

void setDebugOutput(bool enable);
  • enable - If true, enables debug output (ESP-IDF log messages will be sent to this Serial port)

Note: By default, debug output is sent to UART0 (Serial0).

operator bool

Returns whether the Serial port is initialized and ready.

operator bool() const;

Returns: true if the Serial port is initialized, false otherwise.

Example:

Serial1.begin(115200);
while (!Serial1) {
    delay(10);  // Wait for Serial1 to be ready
}

Testing and Helper Functions

The following HAL-level functions are available for testing UART functionality without external hardware connections. These functions use the ESP32 GPIO matrix to create internal loopback connections.

uart_internal_loopback

Creates an internal loopback connection from a UART’s TX signal to a specified RX pin, allowing testing without external wires.

void uart_internal_loopback(uint8_t uartNum, int8_t rxPin);
  • uartNum - UART number (0, 1, 2, etc.)

  • rxPin - GPIO pin number to receive the TX signal

Note: * This function uses the ESP32 GPIO matrix to internally connect the UART’s TX output to the specified RX pin. * LP (Low-Power) UARTs are not supported for loopback. * This is useful for testing UART communication without physical connections.

Example:

Serial1.begin(115200);
Serial1.setPins(RX1, TX1);
uart_internal_loopback(1, RX1);  // Connect TX1 to RX1 internally

uart_internal_hw_flow_ctrl_loopback

Creates an internal loopback connection from a UART’s RTS signal to a specified CTS pin, allowing hardware flow control testing without external wires.

void uart_internal_hw_flow_ctrl_loopback(uint8_t uartNum, int8_t ctsPin);
  • uartNum - UART number (0, 1, 2, etc.)

  • ctsPin - GPIO pin number (CTS pin) to receive the RTS signal

Note: * This function uses the ESP32 GPIO matrix to internally connect the UART’s RTS output to the specified CTS pin. * LP (Low-Power) UARTs are not supported for hardware flow control loopback. * This is useful for testing hardware flow control (RTS/CTS) without physical connections. * Must be used together with uart_internal_loopback() for complete loopback testing with flow control.

Example:

Serial1.begin(115200);
Serial1.setPins(RX1, TX1, CTS_PIN, RTS_PIN);
Serial1.setHwFlowCtrlMode(UART_HW_FLOWCTRL_CTS_RTS);
uart_internal_loopback(1, RX1);  // Connect TX1 to RX1 internally
uart_internal_hw_flow_ctrl_loopback(1, CTS_PIN);  // Connect RTS to CTS internally

Serial Configuration Constants

The following constants are used for serial configuration in the begin() function:

Data Bits, Parity, Stop Bits

  • SERIAL_5N1, SERIAL_5N2, SERIAL_5E1, SERIAL_5E2, SERIAL_5O1, SERIAL_5O2 - 5 data bits

  • SERIAL_6N1, SERIAL_6N2, SERIAL_6E1, SERIAL_6E2, SERIAL_6O1, SERIAL_6O2 - 6 data bits

  • SERIAL_7N1, SERIAL_7N2, SERIAL_7E1, SERIAL_7E2, SERIAL_7O1, SERIAL_7O2 - 7 data bits

  • SERIAL_8N1, SERIAL_8N2, SERIAL_8E1, SERIAL_8E2, SERIAL_8O1, SERIAL_8O2 - 8 data bits

Where: * First number = data bits (5, 6, 7, or 8) * Letter = parity: N (None), E (Even), O (Odd) * Last number = stop bits (1 or 2)

Example Applications

Baud Rate Detection Example:

/*
   This Sketch demonstrates how to detect and set the baud rate when the UART0 is connected to
   some port that is sending data. It can be used with the Arduino IDE Serial Monitor to send the data.

   Serial.begin(0) will start the baud rate detection. Valid range is 300 to 230400 baud.
   It will try to detect for 20 seconds, by default, while reading RX.
   This timeout of 20 seconds can be changed in the begin() function through <<timeout_ms>> parameter:

   void HardwareSerial::begin(baud, config, rxPin, txPin, invert, <<timeout_ms>>, rxfifo_full_thrhd)

   It is necessary that the other end sends some data within <<timeout_ms>>, otherwise the detection won't work.

   IMPORTANT NOTE: baud rate detection seem to only work with ESP32 and ESP32-S2.
   In other other SoCs, it doesn't work.

*/

// Open the Serial Monitor with testing baud start typing and sending characters
void setup() {
  Serial.begin(0);  // it will try to detect the baud rate for 20 seconds

  Serial.print("\n==>The baud rate is ");
  Serial.println(Serial.baudRate());

  //after 20 seconds timeout, when not detected, it will return zero - in this case, we set it back to 115200.
  if (Serial.baudRate() == 0) {
    // Trying to set Serial to a safe state at 115200
    Serial.end();
    Serial.begin(115200);
    Serial.setDebugOutput(true);
    delay(1000);
    log_e("Baud rate detection failed.");
  }
}

void loop() {}

OnReceive Callback Example:

/*

   This Sketch demonstrates how to use onReceive(callbackFunc) with HardwareSerial

   void HardwareSerial::onReceive(OnReceiveCb function, bool onlyOnTimeout = false)

   It is possible to register a UART callback function that will be called
   every time that UART receives data and an associated interrupt is generated.

   The receiving data interrupt can occur because of two possible events:

   1- UART FIFO FULL: it happens when internal UART FIFO reaches a certain number of bytes.
      Its full capacity is 127 bytes. The FIFO Full threshold for the interrupt can be changed
      using HardwareSerial::setRxFIFOFull(uint8_t fifoFull).
      Default FIFO Full Threshold is set at the UART initialization using HardwareSerial::begin()
      This will depend on the baud rate set with when begin() is executed.
      For a baudrate of 115200 or lower, it it just 1 byte, mimicking original Arduino UART driver.
      For a baudrate over 115200 it will be 120 bytes for higher performance.
      Anyway it can be changed by the application at anytime.

   2- UART RX Timeout: it happens, based on a timeout equivalent to a number of symbols at
      the current baud rate. If the UART line is idle for this timeout, it will raise an interrupt.
      This time can be changed by HardwareSerial::setRxTimeout(uint8_t rxTimeout)

   When any of those two interrupts occur, IDF UART driver will copy FIFO data to its internal
   RingBuffer and then Arduino can read such data. At the same time, Arduino Layer will execute
   the callback function defined with HardwareSerial::onReceive().

   <bool onlyOnTimeout> parameter (default false) can be used by the application to tell Arduino to
   only execute the callback when the second event above happens (Rx Timeout). At this time all
   received data will be available to be read by the Arduino application. But if the number of
   received bytes is higher than the FIFO space, it will generate an error of FIFO overflow.
   In order to avoid such problem, the application shall set an appropriate RX buffer size using
   HardwareSerial::setRxBufferSize(size_t new_size) before executing begin() for the Serial port.

   In summary, HardwareSerial::onReceive() works like an RX Interrupt callback, that can be adjusted
   using HardwareSerial::setRxFIFOFull() and HardwareSerial::setRxTimeout().

*/

#include <Arduino.h>

// There are two ways to make this sketch work:
// By physically connecting the pins 4 and 5 and then create a physical UART loopback,
// Or by using the internal IO_MUX to connect the TX signal to the RX pin, creating the
// same loopback internally.
#define USE_INTERNAL_PIN_LOOPBACK 1  // 1 uses the internal loopback, 0 for wiring pins 4 and 5 externally

#define DATA_SIZE 26    // 26 bytes is a lower than RX FIFO size (127 bytes)
#define BAUD      9600  // Any baudrate from 300 to 115200
#define TEST_UART 1     // Serial1 will be used for the loopback testing with different RX FIFO FULL values
#define RXPIN     4     // GPIO 4 => RX for Serial1
#define TXPIN     5     // GPIO 5 => TX for Serial1

uint8_t fifoFullTestCases[] = {120, 20, 5, 1};
// volatile declaration will avoid any compiler optimization when reading variable values
volatile size_t sent_bytes = 0, received_bytes = 0;

void onReceiveFunction(void) {
  // This is a callback function that will be activated on UART RX events
  size_t available = Serial1.available();
  received_bytes = received_bytes + available;
  Serial.printf("onReceive Callback:: There are %zu bytes available: ", available);
  while (available--) {
    Serial.print((char)Serial1.read());
  }
  Serial.println();
}

void setup() {
  // UART0 will be used to log information into Serial Monitor
  Serial.begin(115200);

  // UART1 will have its RX<->TX cross connected
  // GPIO4 <--> GPIO5 using external wire
  Serial1.begin(BAUD, SERIAL_8N1, RXPIN, TXPIN);  // Rx = 4, Tx = 5 will work for ESP32, S2, S3 and C3
#if USE_INTERNAL_PIN_LOOPBACK
  uart_internal_loopback(TEST_UART, RXPIN);
#endif

  for (uint8_t i = 0; i < sizeof(fifoFullTestCases); i++) {
    Serial.printf("\n\n================================\nTest Case #%d\n================================\n", i + 1);
    // onReceive callback will be called on FIFO Full and RX timeout - default behavior
    testAndReport(fifoFullTestCases[i], false);
  }

  Serial.printf("\n\n================================\nTest Case #6\n================================\n");
  // onReceive callback will be called just on RX timeout - using onlyOnTimeout = true
  // FIFO Full parameter (5 bytes) won't matter for the execution of this test case
  // because onReceive() uses only RX Timeout to be activated
  testAndReport(5, true);
}

void loop() {}

void testAndReport(uint8_t fifoFull, bool onlyOnTimeOut) {
  // Let's send 125 bytes from Serial1 rx<->tx and mesaure time using different FIFO Full configurations
  received_bytes = 0;
  sent_bytes = DATA_SIZE;  // 26 characters

  uint8_t dataSent[DATA_SIZE + 1];
  dataSent[DATA_SIZE] = '\0';  // string null terminator, for easy printing.

  // initialize all data
  for (uint8_t i = 0; i < DATA_SIZE; i++) {
    dataSent[i] = 'A' + i;  // fill it with characters A..Z
  }

  Serial.printf("\nTesting onReceive for receiving %zu bytes at %d baud, using RX FIFO Full = %d.\n", sent_bytes, BAUD, fifoFull);
  if (onlyOnTimeOut) {
    Serial.println("onReceive is called just on RX Timeout!");
  } else {
    Serial.println("onReceive is called on both FIFO Full and RX Timeout events.");
  }
  Serial.flush();                                       // wait Serial FIFO to be empty and then spend almost no time processing it
  Serial1.setRxFIFOFull(fifoFull);                      // testing different result based on FIFO Full setup
  Serial1.onReceive(onReceiveFunction, onlyOnTimeOut);  // sets a RX callback function for Serial 1

  sent_bytes = Serial1.write(dataSent, DATA_SIZE);  // ESP32 TX FIFO is about 128 bytes, 125 bytes will fit fine
  Serial.printf("\nSent String: %s\n", dataSent);
  while (received_bytes < sent_bytes) {
    // just wait for receiving all byte in the callback...
  }

  Serial.printf("\nIt has sent %zu bytes from Serial1 TX to Serial1 RX\n", sent_bytes);
  Serial.printf("onReceive() has read a total of %zu bytes\n", received_bytes);
  Serial.println("========================\nFinished!");

  Serial1.onReceive(NULL);  // resets/disables the RX callback function for Serial 1
}

RS485 Communication Example:

/*
  This Sketch demonstrates how to use the Hardware Serial peripheral to communicate over an RS485 bus.

  Data received on the primary serial port is relayed to the bus acting as an RS485 interface and vice versa.

  UART to RS485 translation hardware (e.g., MAX485, MAX33046E, ADM483) is assumed to be configured in half-duplex
  mode with collision detection as described in
  https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/peripherals/uart.html#circuit-a-collision-detection-circuit

  To use the script open the Arduino serial monitor (or alternative serial monitor on the Arduino port). Then,
  using an RS485 tranciver, connect another serial monitor to the RS485 port. Entering data on one terminal
  should be displayed on the other terminal.
*/
#include "hal/uart_types.h"

#define RS485_RX_PIN  16
#define RS485_TX_PIN  5
#define RS485_RTS_PIN 4

#define RS485 Serial1

void setup() {
  Serial.begin(115200);

  RS485.begin(9600, SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
  while (!RS485) {
    delay(10);
  }
  if (!RS485.setPins(-1, -1, -1, RS485_RTS_PIN)) {
    Serial.print("Failed to set RS485 pins");
  }

  // Certain versions of Arduino core don't define MODE_RS485_HALF_DUPLEX and so fail to compile.
  // By using UART_MODE_RS485_HALF_DUPLEX defined in hal/uart_types.h we work around this problem.
  // If using a newer IDF and Arduino core you can omit including hal/uart_types.h and use MODE_RS485_HALF_DUPLEX
  // defined in esp32-hal-uart.h (included during other build steps) instead.
  if (!RS485.setMode(UART_MODE_RS485_HALF_DUPLEX)) {
    Serial.print("Failed to set RS485 mode");
  }
}

void loop() {
  if (RS485.available()) {
    Serial.write(RS485.read());
  }
  if (Serial.available()) {
    RS485.write(Serial.read());
  }
}

Hardware Flow Control Example:

/*
  Hardware Flow Control Demo for ESP32

  This sketch demonstrates UART hardware flow control using RTS (Request To Send)
  and CTS (Clear To Send) signals with UART1 (HardwareSerial Serial1).

  CONFIGURATION:
  ==============

  Set USE_INTERNAL_MATRIX_PIN_LOOPBACK to 1 for internal GPIO matrix connections
  (no external wires needed). Set to 0 to use external wire connections.

  PIN CONNECTIONS (when USE_INTERNAL_MATRIX_PIN_LOOPBACK = 0):
  ============================================================

  For basic loopback with hardware flow control:
  - Connect GPIO2 (RTS1) to GPIO4 (CTS1) - Flow control loopback
  - Connect TX1 pin to RX1 pin - Data loopback

  For GPIO-controlled flow control demonstration:
  - Connect TX1 pin to RX1 pin - Data loopback
  - Connect GPIO2 (RTS1) to GPIO5 (GPIO_RTS_MONITOR) - Monitor RTS state
  - Connect GPIO4 (CTS1) to GPIO13 (GPIO_CTS_CTRL) - Control CTS signal
  - Use GPIO13 to manually control CTS signal (LOW = allow, HIGH = block)

  HARDWARE FLOW CONTROL EXPLANATION:
  ===================================

  RTS (Request To Send):
  - Output signal from UART (GPIO2 in this example)
  - Asserted LOW when UART is ready to receive data (RX buffer has space)
  - De-asserted HIGH when RX buffer is getting full (threshold reached)

  CTS (Clear To Send):
  - Input signal to UART (GPIO4 in this example)
  - UART will only transmit when CTS is LOW (asserted)
  - UART will pause transmission when CTS is HIGH (de-asserted)

  OPERATION:
  ==========

  The sketch demonstrates:
  - Periodic transmission of messages every second
  - Automatic flow control when USE_GPIO_CONTROL = false
  - Manual CTS control when USE_GPIO_CONTROL = true
  - Loopback reception of transmitted data
  - Status monitoring of RTS/CTS pin states

  NOTE: When USE_INTERNAL_MATRIX_PIN_LOOPBACK = 1, no external connections
  are needed as the ESP32 GPIO matrix handles the loopback internally.
*/

// setting it to 1 will allow internal matrix pin connection for RX1<->TX1 and RTS1<->CTS1
// otherwise it needs a wire for cross connecting the pins
#define USE_INTERNAL_MATRIX_PIN_LOOPBACK 1

// Pin definitions for UART1
#define UART1_RX_PIN  RX1  // Default GPIO - UART1 RX pin
#define UART1_TX_PIN  TX1  // Default GPIO - UART1 TX pin
#define UART1_RTS_PIN 2    // GPIO2 - UART1 RTS pin (output from UART)
#define UART1_CTS_PIN 4    // GPIO4 - UART1 CTS pin (input to UART)

// Optional: GPIO pins for manual flow control demonstration
// If using GPIO-controlled flow control, connect:
// - RTS1 to GPIO_RTS_MONITOR (to monitor RTS state)
// - CTS1 to GPIO_CTS_CTRL (to control CTS signal)
#define GPIO_RTS_MONITOR 5   // GPIO5 - Monitor RTS signal (connect RTS1 to this)
#define GPIO_CTS_CTRL    13  // GPIO13 - Control CTS signal (connect CTS1 to this)

// Set to true to use GPIO-controlled flow control, false for simple loopback
// Note: this control will be overridden by USE_INTERNAL_MATRIX_PIN_LOOPBACK when it is 1
#define USE_GPIO_CONTROL false

// Variables for demonstration
unsigned long lastSendTime = 0;
unsigned long lastStatusTime = 0;
const unsigned long sendInterval = 1000;    // Send data every 1 second
const unsigned long statusInterval = 2000;  // Print status every 2 seconds
int sendCounter = 0;

void printPinStatus() {
  Serial.println("\n=== UART1 Pin Status ===");
  Serial.printf("RX Pin (GPIO%d): Receiving data\n", UART1_RX_PIN);
  Serial.printf("TX Pin (GPIO%d): Transmitting data\n", UART1_TX_PIN);

  if (USE_GPIO_CONTROL) {
    // Read RTS state from monitor GPIO (connected to RTS1)
    bool rtsState = digitalRead(GPIO_RTS_MONITOR);
    Serial.printf("RTS Pin (GPIO%d): %s (LOW = ready to receive)\n", UART1_RTS_PIN, rtsState == LOW ? "LOW (Ready)" : "HIGH (Busy)");

    // Read CTS state from control GPIO (connected to CTS1)
    bool ctsState = digitalRead(GPIO_CTS_CTRL);
    Serial.printf("CTS Pin (GPIO%d): %s (LOW = can transmit)\n", UART1_CTS_PIN, ctsState == LOW ? "LOW (Clear)" : "HIGH (Blocked)");
  } else {
    Serial.printf("RTS Pin (GPIO%d): Hardware controlled (LOW = ready to receive)\n", UART1_RTS_PIN);
    Serial.printf("CTS Pin (GPIO%d): Hardware controlled (LOW = can transmit)\n", UART1_CTS_PIN);
    Serial.println("Note: RTS/CTS pins are hardware-controlled. Connect RTS1 to CTS1 for loopback.");
  }

  Serial.printf("Available for write: %d bytes\n", Serial1.availableForWrite());
  Serial.printf("Available to read: %d bytes\n", Serial1.available());
  Serial.println("========================\n");
}

void setup() {
  // Initialize Serial (USB) for debugging
  Serial.begin(115200);
  delay(1000);

  Serial.println("\n\n========================================");
  Serial.println("ESP32 Hardware Flow Control Demo");
  Serial.println("========================================\n");

  // Configure GPIOs for flow control (only if using GPIO-controlled mode)
  if (USE_GPIO_CONTROL) {
    // Configure CTS control GPIO - this will control the CTS signal
    pinMode(GPIO_CTS_CTRL, OUTPUT);
    digitalWrite(GPIO_CTS_CTRL, LOW);  // Start with CTS LOW (clear to send)

    // Configure RTS monitor GPIO - this will monitor the RTS signal
    pinMode(GPIO_RTS_MONITOR, INPUT);
    Serial.println("Using GPIO-controlled flow control mode");
  } else {
    Serial.println("Using hardware-controlled flow control (simple loopback)");
  }

  // Initialize UART1 with hardware flow control
  Serial.println("Initializing UART1...");

  // Begin UART1 with 115200 baud, 8N1 configuration
  Serial1.begin(115200);

  // Set all pins for UART1
  if (!Serial1.setPins(UART1_RX_PIN, UART1_TX_PIN, UART1_CTS_PIN, UART1_RTS_PIN)) {
    Serial.println("ERROR: Failed to set CTS and RTS UART1 pins!");
    while (1) {
      delay(1000);
    }
  }

  Serial.println("Enabling hardware flow control...");
  if (!Serial1.setHwFlowCtrlMode(UART_HW_FLOWCTRL_CTS_RTS, 64)) {
    Serial.println("ERROR: Failed to enable hardware flow control!");
    while (1) {
      delay(1000);
    }
  }

#if USE_INTERNAL_MATRIX_PIN_LOOPBACK
  uart_internal_loopback(1, UART1_RX_PIN);
  uart_internal_hw_flow_ctrl_loopback(1, UART1_CTS_PIN);
#endif

  // Diagnostic: Check initial state after enabling flow control
  Serial.println("\nPost-initialization diagnostics:");
  Serial.printf("  Serial1.available(): %d bytes\n", Serial1.available());
  Serial.printf("  Serial1.availableForWrite(): %d bytes\n", Serial1.availableForWrite());
  if (USE_GPIO_CONTROL) {
    Serial.printf("  GPIO%d (CTS control): %s\n", GPIO_CTS_CTRL, digitalRead(GPIO_CTS_CTRL) == LOW ? "LOW" : "HIGH");
    Serial.printf("  GPIO%d (RTS monitor): %s\n", GPIO_RTS_MONITOR, digitalRead(GPIO_RTS_MONITOR) == LOW ? "LOW" : "HIGH");
  }
  Serial.println();

  Serial.println("UART1 initialized successfully!");
  Serial.println("Hardware flow control: ENABLED (RTS + CTS)");
  Serial.printf("RX Pin: GPIO%d\n", UART1_RX_PIN);
  Serial.printf("TX Pin: GPIO%d\n", UART1_TX_PIN);
  Serial.printf("RTS Pin: GPIO%d (output from UART)\n", UART1_RTS_PIN);
  Serial.printf("CTS Pin: GPIO%d (input to UART)\n", UART1_CTS_PIN);

#if USE_INTERNAL_MATRIX_PIN_LOOPBACK
  Serial.println("\nNO EXTERNAL PIN CONNECTIONS ARE REQUIRED:");
  Serial.println("-------------------------");
  Serial.println("Internal GPIO Matrix connection with flow control mode:");
  Serial.printf("  1. Automatic Internal Connection of GPIO%d (TX1) to GPIO%d (RX1) - Loopback\n", UART1_TX_PIN, UART1_RX_PIN);
  Serial.printf("  2. Automatic Internal Connection of GPIO%d (RTS1) to GPIO%d (CTS1) - Flow control loopback\n", UART1_RTS_PIN, UART1_CTS_PIN);
  Serial.println("\n  Note: In this mode, RTS/CTS are automatically controlled by hardware.");
  Serial.println("  RTS goes LOW when ready to receive, HIGH when buffer is full.");
  Serial.println("  CTS must be LOW for transmission to proceed.");
#else
  Serial.println("\nPIN CONNECTIONS REQUIRED:");
  Serial.println("-------------------------");
  if (USE_GPIO_CONTROL) {
    Serial.println("GPIO-controlled flow control mode:");
    Serial.printf("  1. Connect GPIO%d (TX1) to GPIO%d (RX1) - Loopback\n", UART1_TX_PIN, UART1_RX_PIN);
    Serial.printf("  2. Connect GPIO%d (RTS1) to GPIO%d - Monitor RTS state\n", UART1_RTS_PIN, GPIO_RTS_MONITOR);
    Serial.printf("  3. Connect GPIO%d (CTS1) to GPIO%d - Control CTS signal\n", UART1_CTS_PIN, GPIO_CTS_CTRL);
  } else {
    Serial.println("Hardware-controlled flow control (simple loopback):");
    Serial.printf("  1. Connect GPIO%d (TX1) to GPIO%d (RX1) - Loopback\n", UART1_TX_PIN, UART1_RX_PIN);
    Serial.printf("  2. Connect GPIO%d (RTS1) to GPIO%d (CTS1) - Flow control loopback\n", UART1_RTS_PIN, UART1_CTS_PIN);
    Serial.println("\n  Note: In this mode, RTS/CTS are automatically controlled by hardware.");
    Serial.println("  RTS goes LOW when ready to receive, HIGH when buffer is full.");
    Serial.println("  CTS must be LOW for transmission to proceed.");
  }
#endif
  Serial.println("\nStarting demonstration in 2 seconds...\n");
  delay(2000);
}

void loop() {
  unsigned long currentTime = millis();

  // Print status periodically
  if (currentTime - lastStatusTime >= statusInterval) {
    lastStatusTime = currentTime;
    printPinStatus();

    // Demonstrate flow control by toggling CTS (only in GPIO-controlled mode)
    if (USE_GPIO_CONTROL) {
      static bool ctsState = false;
      ctsState = !ctsState;

      if (ctsState) {
        Serial.println(">>> Blocking transmission (CTS HIGH)...");
        digitalWrite(GPIO_CTS_CTRL, HIGH);  // Block transmission
      } else {
        Serial.println(">>> Allowing transmission (CTS LOW)...");
        digitalWrite(GPIO_CTS_CTRL, LOW);  // Allow transmission
      }
    }
  }

  // Send data periodically
  if (currentTime - lastSendTime >= sendInterval) {
    lastSendTime = currentTime;
    sendCounter++;

    // Check if we can transmit (CTS must be LOW)
    // In GPIO-controlled mode, check the control GPIO; otherwise hardware handles it
    bool canTransmit = true;
    if (USE_GPIO_CONTROL) {
      canTransmit = (digitalRead(GPIO_CTS_CTRL) == LOW);
    }

    if (canTransmit) {
      char message[64];
      snprintf(message, sizeof(message), "Message #%d: Hello from UART1! Time: %lu ms\r\n", sendCounter, currentTime);

      Serial.print("Sending: ");
      Serial.print(message);

      size_t bytesWritten = Serial1.write((const uint8_t *)message, strlen(message));
      Serial.printf("  -> Written: %d bytes\n", bytesWritten);

      // Flush to ensure data is sent
      Serial1.flush();
    } else {
      Serial.println("!!! Transmission blocked - CTS is HIGH !!!");
    }
  }

  // Read and echo received data
  if (Serial1.available()) {
    Serial.print("Received: ");
    while (Serial1.available()) {
      char c = Serial1.read();
      Serial.write(c);
    }
    Serial.println();
  }

  // Small delay to prevent tight loop
  delay(10);
}

Complete list of Serial examples.