diff --git a/cores/esp32/HardwareSerial.cpp b/cores/esp32/HardwareSerial.cpp
index 2f1cb25d5b8..cde85b491bb 100644
--- a/cores/esp32/HardwareSerial.cpp
+++ b/cores/esp32/HardwareSerial.cpp
@@ -5,36 +5,73 @@
 
 #include "pins_arduino.h"
 #include "HardwareSerial.h"
+#include "soc/soc_caps.h"
 
+#ifndef SOC_RX0
 #if CONFIG_IDF_TARGET_ESP32
+#define SOC_RX0 3
+#elif CONFIG_IDF_TARGET_ESP32S2
+#define SOC_RX0 44
+#elif CONFIG_IDF_TARGET_ESP32C3
+#define SOC_RX0 20
+#endif
+#endif
+
+#ifndef SOC_TX0
+#if CONFIG_IDF_TARGET_ESP32
+#define SOC_TX0 1
+#elif CONFIG_IDF_TARGET_ESP32S2
+#define SOC_TX0 43
+#elif CONFIG_IDF_TARGET_ESP32C3
+#define SOC_TX0 21
+#endif
+#endif
+
+void serialEvent(void) __attribute__((weak));
+void serialEvent(void) {}
+
+#if SOC_UART_NUM > 1
 
 #ifndef RX1
+#if CONFIG_IDF_TARGET_ESP32
 #define RX1 9
+#elif CONFIG_IDF_TARGET_ESP32S2
+#define RX1 18
+#elif CONFIG_IDF_TARGET_ESP32C3
+#define RX1 18
+#endif
 #endif
 
 #ifndef TX1
+#if CONFIG_IDF_TARGET_ESP32
 #define TX1 10
+#elif CONFIG_IDF_TARGET_ESP32S2
+#define TX1 17
+#elif CONFIG_IDF_TARGET_ESP32C3
+#define TX1 19
 #endif
+#endif
+
+void serialEvent1(void) __attribute__((weak));
+void serialEvent1(void) {}
+#endif /* SOC_UART_NUM > 1 */
 
+#if SOC_UART_NUM > 2
 #ifndef RX2
+#if CONFIG_IDF_TARGET_ESP32
 #define RX2 16
 #endif
+#endif
 
 #ifndef TX2
+#if CONFIG_IDF_TARGET_ESP32
 #define TX2 17
 #endif
-
-#else
-
-#ifndef RX1
-#define RX1 18
-#endif
-
-#ifndef TX1
-#define TX1 17
 #endif
 
-#endif
+void serialEvent2(void) __attribute__((weak));
+void serialEvent2(void) {}
+#endif /* SOC_UART_NUM > 2 */
 
 #if !defined(NO_GLOBAL_INSTANCES) && !defined(NO_GLOBAL_SERIAL)
 #if ARDUINO_USB_CDC_ON_BOOT //Serial used for USB CDC
@@ -42,50 +79,63 @@ HardwareSerial Serial0(0);
 #else
 HardwareSerial Serial(0);
 #endif
+#if SOC_UART_NUM > 1
 HardwareSerial Serial1(1);
-#if CONFIG_IDF_TARGET_ESP32
+#endif
+#if SOC_UART_NUM > 2
 HardwareSerial Serial2(2);
 #endif
 #endif
 
+void serialEventRun(void)
+{
+#if ARDUINO_USB_CDC_ON_BOOT //Serial used for USB CDC
+    if(Serial0.available()) serialEvent();
+#else
+    if(Serial.available()) serialEvent();
+#endif
+#if SOC_UART_NUM > 1
+    if(Serial1.available()) serialEvent1();
+#endif
+#if SOC_UART_NUM > 2
+    if(Serial2.available()) serialEvent2();
+#endif
+}
+
+
 HardwareSerial::HardwareSerial(int uart_nr) : _uart_nr(uart_nr), _uart(NULL) {}
 
 void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, int8_t txPin, bool invert, unsigned long timeout_ms, uint8_t rxfifo_full_thrhd)
 {
-    if(0 > _uart_nr || _uart_nr > 2) {
-        log_e("Serial number is invalid, please use 0, 1 or 2");
+    if(0 > _uart_nr || _uart_nr >= SOC_UART_NUM) {
+        log_e("Serial number is invalid, please use numers from 0 to %u", SOC_UART_NUM - 1);
         return;
     }
     if(_uart) {
-        end();
+        // in this case it is a begin() over a previous begin() - maybe to change baud rate
+        // thus do not disable debug output
+        end(false);
     }
     if(_uart_nr == 0 && rxPin < 0 && txPin < 0) {
-#if CONFIG_IDF_TARGET_ESP32
-        rxPin = 3;
-        txPin = 1;
-#elif CONFIG_IDF_TARGET_ESP32S2
-        rxPin = 44;
-        txPin = 43;
-#elif CONFIG_IDF_TARGET_ESP32C3
-        rxPin = 20;
-        txPin = 21;
-#endif
+        rxPin = SOC_RX0;
+        txPin = SOC_TX0;
     }
+#if SOC_UART_NUM > 1
     if(_uart_nr == 1 && rxPin < 0 && txPin < 0) {
         rxPin = RX1;
         txPin = TX1;
     }
-#if CONFIG_IDF_TARGET_ESP32
+#endif
+#if SOC_UART_NUM > 2
     if(_uart_nr == 2 && rxPin < 0 && txPin < 0) {
         rxPin = RX2;
         txPin = TX2;
     }
 #endif
-    _uart = uartBegin(_uart_nr, baud ? baud : 9600, config, rxPin, txPin, 256, invert, rxfifo_full_thrhd);
-    _tx_pin = txPin;
-    _rx_pin = rxPin;
 
-    if(!baud) {
+    _uart = uartBegin(_uart_nr, baud ? baud : 9600, config, rxPin, txPin, 256, invert, rxfifo_full_thrhd);
+    if (!baud) {
+        // using baud rate as zero, forces it to try to detect the current baud rate in place
         uartStartDetectBaudrate(_uart);
         time_t startMillis = millis();
         unsigned long detectedBaudRate = 0;
@@ -93,7 +143,7 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in
             yield();
         }
 
-        end();
+        end(false);
 
         if(detectedBaudRate) {
             delay(100); // Give some time...
@@ -101,8 +151,6 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in
         } else {
             log_e("Could not detect baudrate. Serial data at the port must be present within the timeout for detection to be possible");
             _uart = NULL;
-            _tx_pin = 255;
-            _rx_pin = 255;
         }
     }
 }
@@ -112,21 +160,16 @@ void HardwareSerial::updateBaudRate(unsigned long baud)
 	uartSetBaudRate(_uart, baud);
 }
 
-void HardwareSerial::end()
+void HardwareSerial::end(bool turnOffDebug)
 {
-    if(uartGetDebug() == _uart_nr) {
+    if(turnOffDebug && uartGetDebug() == _uart_nr) {
         uartSetDebug(0);
     }
     delay(10);
-    log_v("pins %d %d",_tx_pin, _rx_pin);
-    uartEnd(_uart, _tx_pin, _rx_pin);
+    uartEnd(_uart);
     _uart = 0;
 }
 
-size_t HardwareSerial::setRxBufferSize(size_t new_size) {
-    return uartResizeRxBuffer(_uart, new_size);
-}
-
 void HardwareSerial::setDebugOutput(bool en)
 {
     if(_uart == 0) {
@@ -212,10 +255,16 @@ uint32_t  HardwareSerial::baudRate()
 }
 HardwareSerial::operator bool() const
 {
-    return true;
+    return uartIsDriverInstalled(_uart);
 }
 
 void HardwareSerial::setRxInvert(bool invert)
 {
     uartSetRxInvert(_uart, invert);
 }
+
+void HardwareSerial::setPins(uint8_t rxPin, uint8_t txPin)
+{
+    uartSetPins(_uart, rxPin, txPin);
+}
+
diff --git a/cores/esp32/HardwareSerial.h b/cores/esp32/HardwareSerial.h
index 795b8b68c6d..87807cde8dd 100644
--- a/cores/esp32/HardwareSerial.h
+++ b/cores/esp32/HardwareSerial.h
@@ -49,6 +49,7 @@
 
 #include "Stream.h"
 #include "esp32-hal.h"
+#include "soc/soc_caps.h"
 
 class HardwareSerial: public Stream
 {
@@ -56,7 +57,7 @@ class HardwareSerial: public Stream
     HardwareSerial(int uart_nr);
 
     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 = 112);
-    void end();
+    void end(bool turnOffDebug = true);
     void updateBaudRate(unsigned long baud);
     int available(void);
     int availableForWrite(void);
@@ -98,16 +99,14 @@ class HardwareSerial: public Stream
     uint32_t baudRate();
     operator bool() const;
 
-    size_t setRxBufferSize(size_t);
     void setDebugOutput(bool);
     
     void setRxInvert(bool);
+    void setPins(uint8_t rxPin, uint8_t txPin);
 
 protected:
     int _uart_nr;
     uart_t* _uart;
-    uint8_t _tx_pin;
-    uint8_t _rx_pin;
 };
 
 extern void serialEventRun(void) __attribute__((weak));
@@ -123,8 +122,10 @@ extern HardwareSerial Serial0;
 #else
 extern HardwareSerial Serial;
 #endif
+#if SOC_UART_NUM > 1
 extern HardwareSerial Serial1;
-#if CONFIG_IDF_TARGET_ESP32
+#endif
+#if SOC_UART_NUM > 2
 extern HardwareSerial Serial2;
 #endif
 #endif
diff --git a/cores/esp32/esp32-hal-uart.c b/cores/esp32/esp32-hal-uart.c
index 10b86ceb077..1d8c280b687 100644
--- a/cores/esp32/esp32-hal-uart.c
+++ b/cores/esp32/esp32-hal-uart.c
@@ -14,207 +14,88 @@
 
 #include "esp32-hal-uart.h"
 #include "esp32-hal.h"
+
 #include "freertos/FreeRTOS.h"
-#include "freertos/task.h"
-#include "freertos/queue.h"
 #include "freertos/semphr.h"
-#include "esp_attr.h"
-#include "soc/uart_reg.h"
-#include "soc/uart_struct.h"
-#include "soc/io_mux_reg.h"
-#include "soc/gpio_sig_map.h"
-#include "soc/rtc.h"
-#include "hal/uart_ll.h"
-#include "esp_intr_alloc.h"
-
-#include "esp_system.h"
-#ifdef ESP_IDF_VERSION_MAJOR // IDF 4+
-#if CONFIG_IDF_TARGET_ESP32 // ESP32/PICO-D4
-#include "soc/dport_reg.h"
-#include "esp32/rom/ets_sys.h"
-#include "esp32/rom/uart.h"
-#elif CONFIG_IDF_TARGET_ESP32S2
-#include "soc/dport_reg.h"
-#include "esp32s2/rom/ets_sys.h"
-#include "esp32s2/rom/uart.h"
-#include "soc/periph_defs.h"
-#elif CONFIG_IDF_TARGET_ESP32C3
-#include "esp32c3/rom/ets_sys.h"
-#include "esp32c3/rom/uart.h"
-#include "soc/periph_defs.h"
-#else 
-#error Target CONFIG_IDF_TARGET is not supported
-#endif
-#else // ESP32 Before IDF 4.0
-#include "rom/ets_sys.h"
-#include "rom/uart.h"
-#include "esp_intr.h"
-#endif
 
-#if CONFIG_IDF_TARGET_ESP32
-#define UART_PORTS_NUM 3
-#define UART_REG_BASE(u)    ((u==0)?DR_REG_UART_BASE:(      (u==1)?DR_REG_UART1_BASE:(    (u==2)?DR_REG_UART2_BASE:0)))
-#define UART_RXD_IDX(u)     ((u==0)?U0RXD_IN_IDX:(          (u==1)?U1RXD_IN_IDX:(         (u==2)?U2RXD_IN_IDX:0)))
-#define UART_TXD_IDX(u)     ((u==0)?U0TXD_OUT_IDX:(         (u==1)?U1TXD_OUT_IDX:(        (u==2)?U2TXD_OUT_IDX:0)))
-#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:((u==2)?ETS_UART2_INTR_SOURCE:0)))
-#elif CONFIG_IDF_TARGET_ESP32S2
-#define UART_PORTS_NUM 2
-#define UART_REG_BASE(u)    ((u==0)?DR_REG_UART_BASE:(      (u==1)?DR_REG_UART1_BASE:0))
-#define UART_RXD_IDX(u)     ((u==0)?U0RXD_IN_IDX:(          (u==1)?U1RXD_IN_IDX:0))
-#define UART_TXD_IDX(u)     ((u==0)?U0TXD_OUT_IDX:(         (u==1)?U1TXD_OUT_IDX:0))
-#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:0))
-#else
-#define UART_PORTS_NUM 2
-#define UART_REG_BASE(u)    ((u==0)?DR_REG_UART_BASE:(      (u==1)?DR_REG_UART1_BASE:0))
-#define UART_RXD_IDX(u)     ((u==0)?U0RXD_IN_IDX:(          (u==1)?U1RXD_IN_IDX:0))
-#define UART_TXD_IDX(u)     ((u==0)?U0TXD_OUT_IDX:(         (u==1)?U1TXD_OUT_IDX:0))
-#define UART_INTR_SOURCE(u) ((u==0)?ETS_UART0_INTR_SOURCE:( (u==1)?ETS_UART1_INTR_SOURCE:0))
-#endif
+#include "driver/uart.h"
+#include "hal/uart_ll.h"
+#include "soc/soc_caps.h"
+#include "soc/uart_struct.h"
 
 static int s_uart_debug_nr = 0;
 
 struct uart_struct_t {
-    uart_dev_t * dev;
+
 #if !CONFIG_DISABLE_HAL_LOCKS
     xSemaphoreHandle lock;
 #endif
+
     uint8_t num;
-    xQueueHandle queue;
-    intr_handle_t intr_handle;
+    bool has_peek;
+    uint8_t peek_byte;
+
 };
 
 #if CONFIG_DISABLE_HAL_LOCKS
+
 #define UART_MUTEX_LOCK()
 #define UART_MUTEX_UNLOCK()
 
 static uart_t _uart_bus_array[] = {
-    {&UART0, 0, NULL, NULL},
-    {&UART1, 1, NULL, NULL},
-#if CONFIG_IDF_TARGET_ESP32
-    {&UART2, 2, NULL, NULL}
+    {0, false, 0},
+#if SOC_UART_NUM > 1
+    {1, false, 0},
+#endif
+#if SOC_UART_NUM > 2
+    {2, false, 0},
 #endif
 };
+
 #else
+
 #define UART_MUTEX_LOCK()    do {} while (xSemaphoreTake(uart->lock, portMAX_DELAY) != pdPASS)
 #define UART_MUTEX_UNLOCK()  xSemaphoreGive(uart->lock)
 
 static uart_t _uart_bus_array[] = {
-    {&UART0, NULL, 0, NULL, NULL},
-    {&UART1, NULL, 1, NULL, NULL},
-#if CONFIG_IDF_TARGET_ESP32
-    {&UART2, NULL, 2, NULL, NULL}
+    {NULL, 0, false, 0},
+#if SOC_UART_NUM > 1
+    {NULL, 1, false, 0},
 #endif
-};
+#if SOC_UART_NUM > 2
+    {NULL, 2, false, 0},
 #endif
+};
 
-static void uart_on_apb_change(void * arg, apb_change_ev_t ev_type, uint32_t old_apb, uint32_t new_apb);
-
-static void ARDUINO_ISR_ATTR _uart_isr(void *arg)
-{
-    uint8_t i, c;
-    BaseType_t xHigherPriorityTaskWoken;
-    uart_t* uart;
-
-    for(i=0;i<UART_PORTS_NUM;i++){
-        uart = &_uart_bus_array[i];
-        if(uart->intr_handle == NULL){
-            continue;
-        }
-        uart->dev->int_clr.rxfifo_full = 1;
-        uart->dev->int_clr.frm_err = 1;
-        uart->dev->int_clr.rxfifo_tout = 1;
-#if CONFIG_IDF_TARGET_ESP32
-        while(uart->dev->status.rxfifo_cnt || (uart->dev->mem_rx_status.wr_addr != uart->dev->mem_rx_status.rd_addr)) {
-            c = uart->dev->fifo.rw_byte;
-#else
-        uint32_t fifo_reg = UART_FIFO_AHB_REG(i);
-        while(uart->dev->status.rxfifo_cnt) {
-        	c = ESP_REG(fifo_reg);
-#endif
-            if(uart->queue != NULL) {
-                xQueueSendFromISR(uart->queue, &c, &xHigherPriorityTaskWoken);
-            }
-        }
-    }
-
-    if (xHigherPriorityTaskWoken) {
-        portYIELD_FROM_ISR();
-    }
-}
-
-static void uartEnableInterrupt(uart_t* uart, uint8_t rxfifo_full_thrhd)
-{
-    UART_MUTEX_LOCK();
-    uart->dev->conf1.rxfifo_full_thrhd = rxfifo_full_thrhd;
-#if CONFIG_IDF_TARGET_ESP32
-    uart->dev->conf1.rx_tout_thrhd = 2;
-#else
-    uart->dev->mem_conf.rx_tout_thrhd = 2;
 #endif
-    uart->dev->conf1.rx_tout_en = 1;
-    uart->dev->int_ena.rxfifo_full = 1;
-    uart->dev->int_ena.frm_err = 1;
-    uart->dev->int_ena.rxfifo_tout = 1;
-    uart->dev->int_clr.val = 0xffffffff;
 
-    esp_intr_alloc(UART_INTR_SOURCE(uart->num), (int)ARDUINO_ISR_FLAG, _uart_isr, NULL, &uart->intr_handle);
-    UART_MUTEX_UNLOCK();
-}
-
-static void uartDisableInterrupt(uart_t* uart)
-{
-    UART_MUTEX_LOCK();
-#if CONFIG_IDF_TARGET_ESP32
-    uart->dev->conf1.val = 0;
-#endif
-    uart->dev->int_ena.val = 0;
-    uart->dev->int_clr.val = 0xffffffff;
-
-    esp_intr_free(uart->intr_handle);
-    uart->intr_handle = NULL;
-
-    UART_MUTEX_UNLOCK();
-}
-
-static void uartDetachRx(uart_t* uart, uint8_t rxPin)
+bool uartIsDriverInstalled(uart_t* uart) 
 {
     if(uart == NULL) {
-        return;
+        return 0;
     }
-    pinMatrixInDetach(UART_RXD_IDX(uart->num), false, false);
-    uartDisableInterrupt(uart);
-}
 
-static void uartDetachTx(uart_t* uart, uint8_t txPin)
-{
-    if(uart == NULL) {
-        return;
+    if (uart_is_driver_installed(uart->num)) {
+        return true;
     }
-    pinMatrixOutDetach(txPin, false, false);
+    return false;
 }
 
-static void uartAttachRx(uart_t* uart, uint8_t rxPin, bool inverted, uint8_t rxfifo_full_thrhd)
+void uartSetPins(uart_t* uart, uint8_t rxPin, uint8_t txPin)
 {
-    if(uart == NULL || rxPin >= GPIO_PIN_COUNT) {
+    if(uart == NULL || rxPin >= SOC_GPIO_PIN_COUNT || txPin >= SOC_GPIO_PIN_COUNT) {
         return;
     }
-    pinMode(rxPin, INPUT);
-    uartEnableInterrupt(uart, rxfifo_full_thrhd);
-    pinMatrixInAttach(rxPin, UART_RXD_IDX(uart->num), inverted);
+    UART_MUTEX_LOCK();
+    ESP_ERROR_CHECK(uart_set_pin(uart->num, txPin, rxPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE)); 
+    UART_MUTEX_UNLOCK();
+    
 }
 
-static void uartAttachTx(uart_t* uart, uint8_t txPin, bool inverted)
-{
-    if(uart == NULL || txPin >= GPIO_PIN_COUNT) {
-        return;
-    }
-    pinMode(txPin, OUTPUT);
-    pinMatrixOutAttach(txPin, UART_TXD_IDX(uart->num), inverted, false);
-}
 
 uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t queueLen, bool inverted, uint8_t rxfifo_full_thrhd)
 {
-    if(uart_nr >= UART_PORTS_NUM) {
+    if(uart_nr >= SOC_UART_NUM) {
         return NULL;
     }
 
@@ -224,6 +105,10 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
 
     uart_t* uart = &_uart_bus_array[uart_nr];
 
+    if (uart_is_driver_installed(uart_nr)) {
+        uartEnd(uart);
+    }
+
 #if !CONFIG_DISABLE_HAL_LOCKS
     if(uart->lock == NULL) {
         uart->lock = xSemaphoreCreateMutex();
@@ -233,189 +118,143 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
     }
 #endif
 
-    if(queueLen && uart->queue == NULL) {
-        uart->queue = xQueueCreate(queueLen, sizeof(uint8_t)); //initialize the queue
-        if(uart->queue == NULL) {
-            return NULL;
-        }
-    }
-#if CONFIG_IDF_TARGET_ESP32C3
-
-#else
-    if(uart_nr == 1){
-        DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_UART1_CLK_EN);
-        DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_UART1_RST);
-#if CONFIG_IDF_TARGET_ESP32
-    } else if(uart_nr == 2){
-        DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_UART2_CLK_EN);
-        DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_UART2_RST);
-#endif
-    } else {
-        DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_UART_CLK_EN);
-        DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_UART_RST);
-    }
-#endif
-    uartFlush(uart);
-    uartSetBaudRate(uart, baudrate);
     UART_MUTEX_LOCK();
-    uart->dev->conf0.val = config;
-    #define TWO_STOP_BITS_CONF 0x3
-    #define ONE_STOP_BITS_CONF 0x1
 
-    if ( uart->dev->conf0.stop_bit_num == TWO_STOP_BITS_CONF) {
-        uart->dev->conf0.stop_bit_num = ONE_STOP_BITS_CONF;
-        uart->dev->rs485_conf.dl1_en = 1;
-    }
+    uart_config_t uart_config;
+    uart_config.baud_rate = baudrate;
+    uart_config.data_bits = (config & 0xc) >> 2;
+    uart_config.parity = (config & 0x3);
+    uart_config.stop_bits = (config & 0x30) >> 4;
+    uart_config.flow_ctrl = UART_HW_FLOWCTRL_DISABLE;
+    uart_config.rx_flow_ctrl_thresh = rxfifo_full_thrhd;
+    uart_config.source_clk = UART_SCLK_APB;
 
-    // tx_idle_num : idle interval after tx FIFO is empty(unit: the time it takes to send one bit under current baudrate)
-    // Setting it to 0 prevents line idle time/delays when sending messages with small intervals
-    uart->dev->idle_conf.tx_idle_num = 0;  //
 
-    UART_MUTEX_UNLOCK();
+    ESP_ERROR_CHECK(uart_driver_install(uart_nr, 2*queueLen, 0, 0, NULL, 0));
+    ESP_ERROR_CHECK(uart_param_config(uart_nr, &uart_config));
+    ESP_ERROR_CHECK(uart_set_pin(uart_nr, txPin, rxPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE));
 
-    if(rxPin != -1) {
-        uartAttachRx(uart, rxPin, inverted, rxfifo_full_thrhd);
+    // Is it right or the idea is to swap rx and tx pins? 
+    if (inverted) {
+        // invert signal for both Rx and Tx
+        ESP_ERROR_CHECK(uart_set_line_inverse(uart_nr, UART_SIGNAL_TXD_INV | UART_SIGNAL_RXD_INV));    
     }
 
-    if(txPin != -1) {
-        uartAttachTx(uart, txPin, inverted);
-    }
-    addApbChangeCallback(uart, uart_on_apb_change);
+    UART_MUTEX_UNLOCK();
+
+    uartFlush(uart);
     return uart;
 }
 
-void uartEnd(uart_t* uart, uint8_t txPin, uint8_t rxPin)
+void uartEnd(uart_t* uart)
 {
     if(uart == NULL) {
         return;
     }
-    removeApbChangeCallback(uart, uart_on_apb_change);
-
+   
     UART_MUTEX_LOCK();
-    if(uart->queue != NULL) {
-        vQueueDelete(uart->queue);
-        uart->queue = NULL;
-    }
-
-    uart->dev->conf0.val = 0;
-
+    uart_driver_delete(uart->num);
     UART_MUTEX_UNLOCK();
-
-    uartDetachRx(uart, rxPin);
-    uartDetachTx(uart, txPin);
 }
 
-size_t uartResizeRxBuffer(uart_t * uart, size_t new_size) {
-    if(uart == NULL) {
-        return 0;
-    }
-
-    UART_MUTEX_LOCK();
-    if(uart->queue != NULL) {
-        vQueueDelete(uart->queue);
-        uart->queue = xQueueCreate(new_size, sizeof(uint8_t));
-        if(uart->queue == NULL) {
-            UART_MUTEX_UNLOCK();
-            return 0;
-        }
-    }
-    UART_MUTEX_UNLOCK();
-
-    return new_size;
-}
 
 void uartSetRxInvert(uart_t* uart, bool invert)
 {
     if (uart == NULL)
         return;
+#if 0
+    // POTENTIAL ISSUE :: original code only set/reset rxd_inv bit 
+    // IDF or LL set/reset the whole inv_mask!
+    if (invert)
+        ESP_ERROR_CHECK(uart_set_line_inverse(uart->num, UART_SIGNAL_RXD_INV));
+    else
+        ESP_ERROR_CHECK(uart_set_line_inverse(uart->num, UART_SIGNAL_INV_DISABLE));
     
+#else
+    // this implementation is better over IDF API because it only affects RXD
+    // this is supported in ESP32, ESP32-S2 and ESP32-C3
+    uart_dev_t *hw = UART_LL_GET_HW(uart->num);
     if (invert)
-        uart->dev->conf0.rxd_inv = 1;
+        hw->conf0.rxd_inv = 1;
     else
-        uart->dev->conf0.rxd_inv = 0;
+        hw->conf0.rxd_inv = 0;
+#endif 
 }
 
+
 uint32_t uartAvailable(uart_t* uart)
 {
-    if(uart == NULL || uart->queue == NULL) {
+
+    if(uart == NULL) {
         return 0;
     }
-#ifdef UART_READ_RX_FIFO
-    return (uxQueueMessagesWaiting(uart->queue) + uart->dev->status.rxfifo_cnt) ;
-#else
-    return uxQueueMessagesWaiting(uart->queue);
-#endif
+
+    UART_MUTEX_LOCK();
+    size_t available;
+    uart_get_buffered_data_len(uart->num, &available);
+    if (uart->has_peek) available++;
+    UART_MUTEX_UNLOCK();
+    return available;
 }
 
+
 uint32_t uartAvailableForWrite(uart_t* uart)
 {
     if(uart == NULL) {
         return 0;
     }
-    return 0x7f - uart->dev->status.txfifo_cnt;
-}
-
-#ifdef UART_READ_RX_FIFO
-void uartRxFifoToQueue(uart_t* uart)
-{
-	uint8_t c;
     UART_MUTEX_LOCK();
-	//disable interrupts
-	uart->dev->int_ena.val = 0;
-	uart->dev->int_clr.val = 0xffffffff;
-#if CONFIG_IDF_TARGET_ESP32
-	while (uart->dev->status.rxfifo_cnt || (uart->dev->mem_rx_status.wr_addr != uart->dev->mem_rx_status.rd_addr)) {
-		c = uart->dev->fifo.rw_byte;
-#else
-	uint32_t fifo_reg = UART_FIFO_AHB_REG(uart->num);
-	while (uart->dev->status.rxfifo_cnt) {
-		c = ESP_REG(fifo_reg);
-#endif
-		xQueueSend(uart->queue, &c, 0);
-	}
-	//enable interrupts
-	uart->dev->int_ena.rxfifo_full = 1;
-	uart->dev->int_ena.frm_err = 1;
-	uart->dev->int_ena.rxfifo_tout = 1;
-	uart->dev->int_clr.val = 0xffffffff;
+    uint32_t available =  uart_ll_get_txfifo_len(UART_LL_GET_HW(uart->num));  
     UART_MUTEX_UNLOCK();
+    return available;
 }
-#endif
+
 
 uint8_t uartRead(uart_t* uart)
 {
-    if(uart == NULL || uart->queue == NULL) {
+    if(uart == NULL) {
         return 0;
     }
-    uint8_t c;
-#ifdef UART_READ_RX_FIFO
-    if ((uxQueueMessagesWaiting(uart->queue) == 0) && (uart->dev->status.rxfifo_cnt > 0))
-    {
-    	uartRxFifoToQueue(uart);
-    }
-#endif
-    if(xQueueReceive(uart->queue, &c, 0)) {
-        return c;
+    uint8_t c = 0;
+
+    UART_MUTEX_LOCK();
+
+    if (uart->has_peek) {
+      uart->has_peek = false;
+      c = uart->peek_byte;
+    } else {
+
+        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_RATE_MS);
+        if (len == 0) {
+            c  = 0;
+        }
     }
-    return 0;
+    UART_MUTEX_UNLOCK();
+    return c;
 }
 
 uint8_t uartPeek(uart_t* uart)
 {
-    if(uart == NULL || uart->queue == NULL) {
+    if(uart == NULL) {
         return 0;
     }
-    uint8_t c;
-#ifdef UART_READ_RX_FIFO
-    if ((uxQueueMessagesWaiting(uart->queue) == 0) && (uart->dev->status.rxfifo_cnt > 0))
-    {
-    	uartRxFifoToQueue(uart);
-    }
-#endif
-    if(xQueuePeek(uart->queue, &c, 0)) {
-        return c;
+    uint8_t c = 0;
+
+    UART_MUTEX_LOCK();
+
+    if (uart->has_peek) {
+      c = uart->peek_byte;
+    } else {
+        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_RATE_MS);
+        if (len == 0) {
+            c  = 0;
+        } else {
+            uart->has_peek = true;
+            uart->peek_byte = c;
+        }
     }
-    return 0;
+    UART_MUTEX_UNLOCK();
+    return c;
 }
 
 void uartWrite(uart_t* uart, uint8_t c)
@@ -424,12 +263,7 @@ void uartWrite(uart_t* uart, uint8_t c)
         return;
     }
     UART_MUTEX_LOCK();
-    while(uart->dev->status.txfifo_cnt >= 0x7E);
-#if CONFIG_IDF_TARGET_ESP32
-    uart->dev->fifo.rw_byte = c;
-#else
-    ESP_REG(UART_FIFO_AHB_REG(uart->num)) = c;
-#endif
+    uart_write_bytes(uart->num, &c, 1);
     UART_MUTEX_UNLOCK();
 }
 
@@ -438,25 +272,15 @@ void uartWriteBuf(uart_t* uart, const uint8_t * data, size_t len)
     if(uart == NULL) {
         return;
     }
+
     UART_MUTEX_LOCK();
-#ifndef CONFIG_IDF_TARGET_ESP32
-    uint32_t fifo_reg = UART_FIFO_AHB_REG(uart->num);
-#endif
-    while(len) {
-        while(uart->dev->status.txfifo_cnt >= 0x7E);
-#if CONFIG_IDF_TARGET_ESP32
-        uart->dev->fifo.rw_byte = *data++;
-#else
-        ESP_REG(fifo_reg) = *data++;
-#endif
-        len--;
-    }
+    uart_write_bytes(uart->num, data, len);
     UART_MUTEX_UNLOCK();
 }
 
 void uartFlush(uart_t* uart)
 {
-    uartFlushTxOnly(uart,true);
+    uartFlushTxOnly(uart, true);
 }
 
 void uartFlushTxOnly(uart_t* uart, bool txOnly)
@@ -464,28 +288,13 @@ void uartFlushTxOnly(uart_t* uart, bool txOnly)
     if(uart == NULL) {
         return;
     }
-
-    UART_MUTEX_LOCK();
-#if CONFIG_IDF_TARGET_ESP32
-    while(uart->dev->status.txfifo_cnt || uart->dev->status.st_utx_out);
     
-    if( !txOnly ){
-        //Due to hardware issue, we can not use fifo_rst to reset uart fifo.
-        //See description about UART_TXFIFO_RST and UART_RXFIFO_RST in <<esp32_technical_reference_manual>> v2.6 or later.
-
-        // we read the data out and make `fifo_len == 0 && rd_addr == wr_addr`.
-        while(uart->dev->status.rxfifo_cnt != 0 || (uart->dev->mem_rx_status.wr_addr != uart->dev->mem_rx_status.rd_addr)) {
-            READ_PERI_REG(UART_FIFO_REG(uart->num));
-        }
+    UART_MUTEX_LOCK();
+    ESP_ERROR_CHECK(uart_wait_tx_done(uart->num, portMAX_DELAY));
 
-        xQueueReset(uart->queue);
+    if ( !txOnly ) {
+        ESP_ERROR_CHECK(uart_flush_input(uart->num));
     }
-#else
-    while(uart->dev->status.txfifo_cnt);
-    uart->dev->conf0.txfifo_rst = 1;
-    uart->dev->conf0.txfifo_rst = 0;
-#endif
-    
     UART_MUTEX_UNLOCK();
 }
 
@@ -495,100 +304,41 @@ void uartSetBaudRate(uart_t* uart, uint32_t baud_rate)
         return;
     }
     UART_MUTEX_LOCK();
-    uart_ll_set_baudrate(uart->dev, baud_rate);
+    uart_ll_set_baudrate(UART_LL_GET_HW(uart->num), baud_rate);
     UART_MUTEX_UNLOCK();
 }
 
-static void uart_on_apb_change(void * arg, apb_change_ev_t ev_type, uint32_t old_apb, uint32_t new_apb)
-{
-    uart_t* uart = (uart_t*)arg;
-    if(ev_type == APB_BEFORE_CHANGE){
-        UART_MUTEX_LOCK();
-        //disabple interrupt
-        uart->dev->int_ena.val = 0;
-        uart->dev->int_clr.val = 0xffffffff;
-        // read RX fifo
-        uint8_t c;
-   //     BaseType_t xHigherPriorityTaskWoken;
-#if CONFIG_IDF_TARGET_ESP32
-        while(uart->dev->status.rxfifo_cnt != 0 || (uart->dev->mem_rx_status.wr_addr != uart->dev->mem_rx_status.rd_addr)) {
-            c = uart->dev->fifo.rw_byte;
-#else
-        uint32_t fifo_reg = UART_FIFO_AHB_REG(uart->num);
-        while(uart->dev->status.rxfifo_cnt != 0) {
-            c = ESP_REG(fifo_reg);
-#endif
-            if(uart->queue != NULL ) {
-                xQueueSend(uart->queue, &c, 1); //&xHigherPriorityTaskWoken);
-            }
-        }
-        UART_MUTEX_UNLOCK();
- 
-        // wait TX empty
-#if CONFIG_IDF_TARGET_ESP32
-        while(uart->dev->status.txfifo_cnt || uart->dev->status.st_utx_out);
-#else
-        while(uart->dev->status.txfifo_cnt);
-#endif
-    } else {
-        //todo:
-        // set baudrate
-        UART_MUTEX_LOCK();
-        uint32_t clk_div = (uart->dev->clk_div.div_int << 4) | (uart->dev->clk_div.div_frag & 0x0F);
-        uint32_t baud_rate = ((old_apb<<4)/clk_div);
-        clk_div = ((new_apb<<4)/baud_rate);
-        uart->dev->clk_div.div_int = clk_div>>4 ;
-        uart->dev->clk_div.div_frag = clk_div & 0xf;
-        //enable interrupts
-        uart->dev->int_ena.rxfifo_full = 1;
-        uart->dev->int_ena.frm_err = 1;
-        uart->dev->int_ena.rxfifo_tout = 1;
-        uart->dev->int_clr.val = 0xffffffff;
-        UART_MUTEX_UNLOCK();
-    }
-}
-
 uint32_t uartGetBaudRate(uart_t* uart)
 {
     if(uart == NULL) {
         return 0;
     }
 
-    uint32_t clk_div = (uart->dev->clk_div.div_int << 4) | (uart->dev->clk_div.div_frag & 0x0F);
-    if(!clk_div) {
-        return 0;
-    }
-
-    return ((getApbFrequency()<<4)/clk_div);
+    UART_MUTEX_LOCK();
+    uint32_t baud_rate = uart_ll_get_baudrate(UART_LL_GET_HW(uart->num));
+    UART_MUTEX_UNLOCK();
+    return baud_rate;
 }
 
 static void ARDUINO_ISR_ATTR uart0_write_char(char c)
 {
-#if CONFIG_IDF_TARGET_ESP32
-    while(((ESP_REG(0x01C+DR_REG_UART_BASE) >> UART_TXFIFO_CNT_S) & 0x7F) >= 0x7E);
-    ESP_REG(DR_REG_UART_BASE) = c;
-#else
-    while(UART0.status.txfifo_cnt == 0x7F);
-    WRITE_PERI_REG(UART_FIFO_AHB_REG(0), c);
-#endif
+    while (uart_ll_get_txfifo_len(&UART0) == 0);
+    uart_ll_write_txfifo(&UART0, (const uint8_t *) &c, 1);
 }
 
+#if SOC_UART_NUM > 1
 static void ARDUINO_ISR_ATTR uart1_write_char(char c)
 {
-#if CONFIG_IDF_TARGET_ESP32
-    while(((ESP_REG(0x01C+DR_REG_UART1_BASE) >> UART_TXFIFO_CNT_S) & 0x7F) >= 0x7E);
-    ESP_REG(DR_REG_UART1_BASE) = c;
-#else
-    while(UART1.status.txfifo_cnt == 0x7F);
-    WRITE_PERI_REG(UART_FIFO_AHB_REG(1), c);
-#endif
+    while (uart_ll_get_txfifo_len(&UART1) == 0);
+    uart_ll_write_txfifo(&UART1, (const uint8_t *) &c, 1);
 }
+#endif
 
-#if CONFIG_IDF_TARGET_ESP32
+#if SOC_UART_NUM > 2
 static void ARDUINO_ISR_ATTR uart2_write_char(char c)
 {
-    while(((ESP_REG(0x01C+DR_REG_UART2_BASE) >> UART_TXFIFO_CNT_S) & 0x7F) >= 0x7E);
-    ESP_REG(DR_REG_UART2_BASE) = c;
+    while (uart_ll_get_txfifo_len(&UART2) == 0);
+    uart_ll_write_txfifo(&UART2, (const uint8_t *) &c, 1);
 }
 #endif
 
@@ -598,10 +348,12 @@ void uart_install_putc()
     case 0:
         ets_install_putc1((void (*)(char)) &uart0_write_char);
         break;
+#if SOC_UART_NUM > 1
     case 1:
         ets_install_putc1((void (*)(char)) &uart1_write_char);
         break;
-#if CONFIG_IDF_TARGET_ESP32
+#endif
+#if SOC_UART_NUM > 2
     case 2:
         ets_install_putc1((void (*)(char)) &uart2_write_char);
         break;
@@ -614,7 +366,7 @@ void uart_install_putc()
 
 void uartSetDebug(uart_t* uart)
 {
-    if(uart == NULL || uart->num >= UART_PORTS_NUM) {
+    if(uart == NULL || uart->num >= SOC_UART_NUM) {
         s_uart_debug_nr = -1;
         //ets_install_putc1(NULL);
         //return;
@@ -669,6 +421,7 @@ int log_printf(const char *format, ...)
     return len;
 }
 
+
 static void log_print_buf_line(const uint8_t *b, size_t len, size_t total_len){
     for(size_t i = 0; i<len; i++){
         log_printf("%s0x%02x,",i?" ":"", b[i]);
@@ -705,42 +458,89 @@ void log_print_buf(const uint8_t *b, size_t len){
  */
 unsigned long uartBaudrateDetect(uart_t *uart, bool flg)
 {
-    while(uart->dev->rxd_cnt.edge_cnt < 30) { // UART_PULSE_NUM(uart_num)
+    if(uart == NULL) {
+        return 0;
+    }
+
+    uart_dev_t *hw = UART_LL_GET_HW(uart->num);
+
+    while(hw->rxd_cnt.edge_cnt < 30) { // UART_PULSE_NUM(uart_num)
         if(flg) return 0;
         ets_delay_us(1000);
     }
 
     UART_MUTEX_LOCK();
-    unsigned long ret = ((uart->dev->lowpulse.min_cnt + uart->dev->highpulse.min_cnt) >> 1) + 12;
+    //log_i("lowpulse_min_cnt = %d hightpulse_min_cnt = %d", hw->lowpulse.min_cnt, hw->highpulse.min_cnt);
+    unsigned long ret = ((hw->lowpulse.min_cnt + hw->highpulse.min_cnt) >> 1);
     UART_MUTEX_UNLOCK();
 
     return ret;
 }
 
+
 /*
  * To start detection of baud rate with the uart the auto_baud.en bit needs to be cleared and set. The bit period is 
  * detected calling uartBadrateDetect(). The raw baudrate is computed using the UART_CLK_FREQ. The raw baudrate is 
  * rounded to the closed real baudrate.
+ * 
+ * ESP32-C3 reports wrong baud rate detection as shown below:
+ * 
+ * This will help in a future recall for the C3.
+ * Baud Sent:          Baud Read:
+ *  300        -->       19536
+ * 2400        -->       19536
+ * 4800        -->       19536 
+ * 9600        -->       28818 
+ * 19200       -->       57678
+ * 38400       -->       115440
+ * 57600       -->       173535
+ * 115200      -->       347826
+ * 230400      -->       701754
+ * 
+ * 
 */
 void uartStartDetectBaudrate(uart_t *uart) {
-  if(!uart) return;
-#ifndef CONFIG_IDF_TARGET_ESP32C3
-  uart->dev->auto_baud.glitch_filt = 0x08;
-  uart->dev->auto_baud.en = 0;
-  uart->dev->auto_baud.en = 1;
+    if(uart == NULL) {
+        return;
+    }
+
+    uart_dev_t *hw = UART_LL_GET_HW(uart->num);
+
+#ifdef CONFIG_IDF_TARGET_ESP32C3
+    
+    // ESP32-C3 requires further testing
+    // Baud rate detection returns wrong values 
+   
+    log_e("ESP32-C3 baud rate detection is not supported.");
+    return;
+
+    // Code bellow for C3 kept for future recall
+    //hw->rx_filt.glitch_filt = 0x08;
+    //hw->rx_filt.glitch_filt_en = 1;
+    //hw->conf0.autobaud_en = 0;
+    //hw->conf0.autobaud_en = 1;
+
+#else
+    hw->auto_baud.glitch_filt = 0x08;
+    hw->auto_baud.en = 0;
+    hw->auto_baud.en = 1;
 #endif
 }
-
+ 
 unsigned long
 uartDetectBaudrate(uart_t *uart)
 {
-#ifndef CONFIG_IDF_TARGET_ESP32C3
+    if(uart == NULL) {
+        return 0;
+    }
+
+#ifndef CONFIG_IDF_TARGET_ESP32C3    // ESP32-C3 requires further testing - Baud rate detection returns wrong values 
+
     static bool uartStateDetectingBaudrate = false;
+    uart_dev_t *hw = UART_LL_GET_HW(uart->num);
 
     if(!uartStateDetectingBaudrate) {
-        uart->dev->auto_baud.glitch_filt = 0x08;
-        uart->dev->auto_baud.en = 0;
-        uart->dev->auto_baud.en = 1;
+        uartStartDetectBaudrate(uart);
         uartStateDetectingBaudrate = true;
     }
 
@@ -748,11 +548,21 @@ uartDetectBaudrate(uart_t *uart)
     if (!divisor) {
         return 0;
     }
+    //  log_i(...) below has been used to check C3 baud rate detection results
+    //log_i("Divisor = %d\n", divisor);
+    //log_i("BAUD RATE based on Positive Pulse %d\n", getApbFrequency()/((hw->pospulse.min_cnt + 1)/2));
+    //log_i("BAUD RATE based on Negative Pulse %d\n", getApbFrequency()/((hw->negpulse.min_cnt + 1)/2));
+
 
-    uart->dev->auto_baud.en = 0;
+#ifdef CONFIG_IDF_TARGET_ESP32C3
+    //hw->conf0.autobaud_en = 0;
+#else
+    hw->auto_baud.en = 0;
+#endif
     uartStateDetectingBaudrate = false; // Initialize for the next round
 
     unsigned long baudrate = getApbFrequency() / divisor;
+    //log_i("APB_FREQ = %d\nraw baudrate detected = %d", getApbFrequency(), baudrate);
 
     static const unsigned long default_rates[] = {300, 600, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 74880, 115200, 230400, 256000, 460800, 921600, 1843200, 3686400};
 
@@ -770,17 +580,7 @@ uartDetectBaudrate(uart_t *uart)
 
     return default_rates[i];
 #else
-    return 0;
-#endif
-}
-
-/*
- * Returns the status of the RX state machine, if the value is non-zero the state machine is active.
- */
-bool uartRxActive(uart_t* uart) {
-#if CONFIG_IDF_TARGET_ESP32
-    return uart->dev->status.st_urx_out != 0;
-#else
+    log_e("ESP32-C3 baud rate detection is not supported.");
     return 0;
 #endif
 }
diff --git a/cores/esp32/esp32-hal-uart.h b/cores/esp32/esp32-hal-uart.h
index 9e8e7ad0d36..609f380f59e 100644
--- a/cores/esp32/esp32-hal-uart.h
+++ b/cores/esp32/esp32-hal-uart.h
@@ -52,7 +52,7 @@ struct uart_struct_t;
 typedef struct uart_struct_t uart_t;
 
 uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t queueLen, bool inverted, uint8_t rxfifo_full_thrhd);
-void uartEnd(uart_t* uart, uint8_t rxPin, uint8_t txPin);
+void uartEnd(uart_t* uart);
 
 uint32_t uartAvailable(uart_t* uart);
 uint32_t uartAvailableForWrite(uart_t* uart);
@@ -68,17 +68,17 @@ void uartFlushTxOnly(uart_t* uart, bool txOnly );
 void uartSetBaudRate(uart_t* uart, uint32_t baud_rate);
 uint32_t uartGetBaudRate(uart_t* uart);
 
-size_t uartResizeRxBuffer(uart_t* uart, size_t new_size);
-
 void uartSetRxInvert(uart_t* uart, bool invert);
 
 void uartSetDebug(uart_t* uart);
 int uartGetDebug();
 
+bool uartIsDriverInstalled(uart_t* uart);
+void uartSetPins(uart_t* uart, uint8_t rxPin, uint8_t txPin);
+
 void uartStartDetectBaudrate(uart_t *uart);
 unsigned long uartDetectBaudrate(uart_t *uart);
 
-bool uartRxActive(uart_t* uart);
 
 #ifdef __cplusplus
 }