diff --git a/cores/esp32/HardwareSerial.cpp b/cores/esp32/HardwareSerial.cpp
index 7792b8e039b..10a6bc1ca1d 100644
--- a/cores/esp32/HardwareSerial.cpp
+++ b/cores/esp32/HardwareSerial.cpp
@@ -114,7 +114,7 @@ _eventTask(NULL)
 
 HardwareSerial::~HardwareSerial()
 {
-    end(true); // explicit Full UART termination
+    end(); // explicit Full UART termination
 #if !CONFIG_DISABLE_HAL_LOCKS
     if(_lock != NULL){
         vSemaphoreDelete(_lock);
@@ -329,16 +329,22 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in
     // map logical pins to GPIO numbers
     rxPin = digitalPinToGPIONumber(rxPin);
     txPin = digitalPinToGPIONumber(txPin);
+    // IDF UART driver keeps Pin setting on restarting. Negative Pin number will keep it unmodified.
+    // it will detach previous UART attached pins
 
-    if(_uart) {
-        // in this case it is a begin() over a previous begin() - maybe to change baud rate
-        // thus do not disable debug output
-        end(false);  // disables IDF UART driver and UART event Task + sets _uart to NULL
+    // indicates that uartbegin() has to initilize a new IDF driver
+    if (_testUartBegin(_uart_nr, baud ? baud : 9600, config, rxPin, txPin, _rxBufferSize, _txBufferSize, invert, rxfifo_full_thrhd)) {
+        _destroyEventTask(); // when IDF uart driver must be restarted, _eventTask must finish too
     }
 
     // IDF UART driver keeps Pin setting on restarting. Negative Pin number will keep it unmodified.
     // it will detach previous UART attached pins
     _uart = uartBegin(_uart_nr, baud ? baud : 9600, config, rxPin, txPin, _rxBufferSize, _txBufferSize, invert, rxfifo_full_thrhd);
+    if (_uart == NULL) {
+        log_e("UART driver failed to start. Please check the logs.");
+        HSERIAL_MUTEX_UNLOCK();
+        return;
+    }
     if (!baud) {
         // using baud rate as zero, forces it to try to detect the current baud rate in place
         uartStartDetectBaudrate(_uart);
@@ -348,11 +354,14 @@ void HardwareSerial::begin(unsigned long baud, uint32_t config, int8_t rxPin, in
             yield();
         }
 
-        end(false);  // disables IDF UART driver and UART event Task + sets _uart to NULL
-
         if(detectedBaudRate) {
             delay(100); // Give some time...
             _uart = uartBegin(_uart_nr, detectedBaudRate, config, rxPin, txPin, _rxBufferSize, _txBufferSize, invert, rxfifo_full_thrhd);
+            if (_uart == NULL) {
+                log_e("UART driver failed to start. Please check the logs.");
+                HSERIAL_MUTEX_UNLOCK();
+                return;
+            }
         } 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;
@@ -389,22 +398,17 @@ void HardwareSerial::updateBaudRate(unsigned long baud)
   uartSetBaudRate(_uart, baud);
 }
 
-void HardwareSerial::end(bool fullyTerminate)
+void HardwareSerial::end()
 {
     // default Serial.end() will completely disable HardwareSerial,
     // including any tasks or debug message channel (log_x()) - but not for IDF log messages!
-    if(fullyTerminate) {
-        _onReceiveCB = NULL;
-        _onReceiveErrorCB = NULL;
-        if (uartGetDebug() == _uart_nr) {
-            uartSetDebug(0);
-        }
-        _rxFIFOFull = 0;
-        uartEnd(_uart_nr);  // fully detach all pins and delete the UART driver
-    } else {
-      // do not invalidate callbacks, detach pins, invalidate DBG output
-      uart_driver_delete(_uart_nr);
+    _onReceiveCB = NULL;
+    _onReceiveErrorCB = NULL;
+    if (uartGetDebug() == _uart_nr) {
+        uartSetDebug(0);
     }
+    _rxFIFOFull = 0;
+    uartEnd(_uart_nr);  // fully detach all pins and delete the UART driver
     _destroyEventTask(); // when IDF uart driver is deleted, _eventTask must finish too
     _uart = NULL;
 }
@@ -564,3 +568,4 @@ size_t HardwareSerial::setTxBufferSize(size_t new_size) {
     _txBufferSize = new_size;
     return _txBufferSize;
 }
+
diff --git a/cores/esp32/HardwareSerial.h b/cores/esp32/HardwareSerial.h
index 688655f4f21..0bf72d2aff2 100644
--- a/cores/esp32/HardwareSerial.h
+++ b/cores/esp32/HardwareSerial.h
@@ -252,7 +252,7 @@ class HardwareSerial: public Stream
     // invert will invert RX/TX polarity
     // rxfifo_full_thrhd if the UART Flow Control Threshold in the UART FIFO (max 127)
     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(bool fullyTerminate = true);
+    void end(void);
     void updateBaudRate(unsigned long baud);
     int available(void);
     int availableForWrite(void);
diff --git a/cores/esp32/esp32-hal-uart.c b/cores/esp32/esp32-hal-uart.c
index 3d3559f7dec..b22267fbc68 100644
--- a/cores/esp32/esp32-hal-uart.c
+++ b/cores/esp32/esp32-hal-uart.c
@@ -1,4 +1,4 @@
-// Copyright 2015-2023 Espressif Systems (Shanghai) PTE LTD
+// Copyright 2015-2024 Espressif Systems (Shanghai) PTE LTD
 //
 // Licensed under the Apache License, Version 2.0 (the "License");
 // you may not use this file except in compliance with the License.
@@ -33,19 +33,25 @@
 #include "hal/gpio_hal.h"
 #include "esp_rom_gpio.h"
 
-static int s_uart_debug_nr = 0;
+static int s_uart_debug_nr = 0;               // UART number for debug output
 
 struct uart_struct_t {
 
 #if !CONFIG_DISABLE_HAL_LOCKS
-    SemaphoreHandle_t lock;
+    SemaphoreHandle_t lock;                   // UART lock
 #endif
 
-    uint8_t num;
-    bool has_peek;
-    uint8_t peek_byte;
-    QueueHandle_t uart_event_queue;   // export it by some uartGetEventQueue() function
-    int8_t _rxPin, _txPin, _ctsPin, _rtsPin; // UART GPIOs
+    uint8_t num;                               // UART number for IDF driver API
+    bool has_peek;                             // flag to indicate that there is a peek byte pending to be read
+    uint8_t peek_byte;                         // peek byte that has been read but not consumed
+    QueueHandle_t uart_event_queue;            // export it by some uartGetEventQueue() function
+    // configuration data:: Arduino API tipical data
+    int8_t _rxPin, _txPin, _ctsPin, _rtsPin;   // UART GPIOs
+    uint32_t _baudrate, _config;               // UART baudrate and config
+    // UART ESP32 specific data
+    uint16_t _rx_buffer_size, _tx_buffer_size; // UART RX and TX buffer sizes
+    bool _inverted;                            // UART inverted signal
+    uint8_t _rxfifo_full_thrhd;                // UART RX FIFO full threshold
 };
 
 #if CONFIG_DISABLE_HAL_LOCKS
@@ -54,12 +60,12 @@ struct uart_struct_t {
 #define UART_MUTEX_UNLOCK()
 
 static uart_t _uart_bus_array[] = {
-    {0, false, 0, NULL, -1, -1, -1, -1},
+    {0, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #if SOC_UART_NUM > 1
-    {1, false, 0, NULL, -1, -1, -1, -1},
+    {1, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #endif
 #if SOC_UART_NUM > 2
-    {2, false, 0, NULL, -1, -1, -1, -1},
+    {2, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #endif
 };
 
@@ -69,12 +75,12 @@ static uart_t _uart_bus_array[] = {
 #define UART_MUTEX_UNLOCK()  if(uart->lock != NULL) xSemaphoreGive(uart->lock)
 
 static uart_t _uart_bus_array[] = {
-    {NULL, 0, false, 0, NULL, -1, -1, -1, -1},
+    {NULL, 0, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #if SOC_UART_NUM > 1
-    {NULL, 1, false, 0, NULL, -1, -1, -1, -1},
+    {NULL, 1, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #endif
 #if SOC_UART_NUM > 2
-    {NULL, 2, false, 0, NULL, -1, -1, -1, -1},
+    {NULL, 2, false, 0, NULL, -1, -1, -1, -1, 0, 0, 0, 0, false, 0},
 #endif
 };
 
@@ -97,7 +103,12 @@ static bool _uartDetachPins(uint8_t uart_num, int8_t rxPin, int8_t txPin, int8_t
     // detaches pins and sets Peripheral Manager and UART information
     if (rxPin >= 0 && uart->_rxPin == rxPin && perimanGetPinBusType(rxPin) == ESP32_BUS_TYPE_UART_RX) {
         gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[rxPin], PIN_FUNC_GPIO);
-        esp_rom_gpio_connect_in_signal(GPIO_FUNC_IN_LOW, UART_PERIPH_SIGNAL(uart_num, SOC_UART_RX_PIN_IDX), false);
+        // avoids causing BREAK in the UART line
+        if (uart->_inverted) {
+            esp_rom_gpio_connect_in_signal(GPIO_FUNC_IN_LOW, UART_PERIPH_SIGNAL(uart_num, SOC_UART_RX_PIN_IDX), false);
+        } else {
+            esp_rom_gpio_connect_in_signal(GPIO_FUNC_IN_HIGH, UART_PERIPH_SIGNAL(uart_num, SOC_UART_RX_PIN_IDX), false);
+        }
         uart->_rxPin = -1;  // -1 means unassigned/detached
         if (!perimanClearPinBus(rxPin)) {
             retCode = false;
@@ -355,28 +366,121 @@ bool uartSetHwFlowCtrlMode(uart_t *uart, uart_hw_flowcontrol_t mode, uint8_t thr
     return retCode;
 }
 
-uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t rx_buffer_size, uint16_t tx_buffer_size, bool inverted, uint8_t rxfifo_full_thrhd)
+// This helper function will return true if a new IDF UART driver needs to be restarted and false if the current one can continue its execution
+bool _testUartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t rx_buffer_size, uint16_t tx_buffer_size, bool inverted, uint8_t rxfifo_full_thrhd)
 {
     if(uart_nr >= SOC_UART_NUM) {
-        return NULL;
+        return false;  // no new driver has to be installed
     }
     uart_t* uart = &_uart_bus_array[uart_nr];
-
+    // verify if is necessary to restart the UART driver
     if (uart_is_driver_installed(uart_nr)) {
-        uartEnd(uart_nr);
+        // some parameters can't be changed unless we end the UART driver
+        if ( uart->_rx_buffer_size != rx_buffer_size || uart->_tx_buffer_size != tx_buffer_size || uart->_inverted != inverted || uart->_rxfifo_full_thrhd != rxfifo_full_thrhd) {
+            return true;   // the current IDF UART driver must be terminated and a new driver shall be installed
+        } else {
+            return false;  // The current IDF UART driver can continue its execution
+        }
+    } else {
+        return true;       // no IDF UART driver is running and a new driver shall be installed
     }
+}
+
+uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t rx_buffer_size, uint16_t tx_buffer_size, bool inverted, uint8_t rxfifo_full_thrhd)
+{
+    if(uart_nr >= SOC_UART_NUM) {
+        log_e("UART number is invalid, please use number from 0 to %u", SOC_UART_NUM - 1);
+        return NULL;  // no new driver was installed
+    }
+    uart_t* uart = &_uart_bus_array[uart_nr];
+    log_v("UART%d baud(%ld) Mode(%x) rxPin(%d) txPin(%d)", uart_nr, baudrate, config, rxPin, txPin);
 
 #if !CONFIG_DISABLE_HAL_LOCKS
     if(uart->lock == NULL) {
         uart->lock = xSemaphoreCreateMutex();
         if(uart->lock == NULL) {
             log_e("HAL LOCK error.");
-            return NULL;
+            return NULL; // no new driver was installed
         }
     }
 #endif
-    UART_MUTEX_LOCK();
 
+    if (uart_is_driver_installed(uart_nr)) {
+        log_v("UART%d Driver already installed.", uart_nr);
+        // some parameters can't be changed unless we end the UART driver
+        if ( uart->_rx_buffer_size != rx_buffer_size || uart->_tx_buffer_size != tx_buffer_size || uart->_inverted != inverted || uart->_rxfifo_full_thrhd != rxfifo_full_thrhd) {
+            log_v("UART%d changing buffer sizes or inverted signal or rxfifo_full_thrhd. IDF driver will be restarted", uart_nr);
+            uartEnd(uart_nr);
+        } else {
+            bool retCode = true;
+            UART_MUTEX_LOCK();
+            //User may just want to change some parameters, such as baudrate, data length, parity, stop bits or pins
+            if (uart->_baudrate != baudrate) {
+                if (ESP_OK != uart_set_baudrate(uart_nr, baudrate)) {
+                    log_e("UART%d changing baudrate failed.", uart_nr);
+                    retCode = false;
+                } else {
+                    log_v("UART%d changed baudrate to %d", uart_nr, baudrate);
+                    uart->_baudrate = baudrate;
+                }   
+            }
+            uart_word_length_t data_bits = (config & 0xc) >> 2;
+            uart_parity_t parity = config & 0x3;
+            uart_stop_bits_t stop_bits = (config & 0x30) >> 4;
+            if (retCode && (uart->_config & 0xc) >> 2 != data_bits) {
+                if (ESP_OK != uart_set_word_length(uart_nr, data_bits)) {
+                    log_e("UART%d changing data length failed.", uart_nr);
+                    retCode = false;
+                } else {
+                    log_v("UART%d changed data length to %d", uart_nr, data_bits + 5);
+                }
+            }
+            if (retCode && (uart->_config & 0x3) != parity) {
+                if (ESP_OK != uart_set_parity(uart_nr, parity)) {
+                    log_e("UART%d changing parity failed.", uart_nr);
+                    retCode = false;
+                } else {
+                    log_v("UART%d changed parity to %s", uart_nr, parity == 0 ? "NONE" : parity == 2 ? "EVEN" : "ODD");
+                }                
+            }
+            if (retCode && (uart->_config & 0xc30) >> 4 != stop_bits) {
+                if (ESP_OK != uart_set_stop_bits(uart_nr, stop_bits)) {
+                    log_e("UART%d changing stop bits failed.", uart_nr);
+                    retCode = false;
+                } else {
+                    log_v("UART%d changed stop bits to %d", uart_nr, stop_bits == 3 ? 2 : 1);
+                }                
+            }
+            if (retCode) uart->_config = config;
+            if (retCode && rxPin > 0 && uart->_rxPin != rxPin) {
+                retCode &= _uartDetachPins(uart_nr, uart->_rxPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
+                retCode &= _uartAttachPins(uart_nr, rxPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
+                if (!retCode) {
+                    log_e("UART%d changing RX pin failed.", uart_nr);
+                } else {
+                    log_v("UART%d changed RX pin to %d", uart_nr, rxPin);
+                }
+            }
+            if (retCode && txPin > 0 && uart->_txPin != txPin) {
+                retCode &= _uartDetachPins(uart_nr, UART_PIN_NO_CHANGE, uart->_txPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
+                retCode &= _uartAttachPins(uart_nr, UART_PIN_NO_CHANGE, txPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
+                if (!retCode) {
+                    log_e("UART%d changing TX pin failed.", uart_nr);
+                } else {
+                    log_v("UART%d changed TX pin to %d", uart_nr, txPin);
+                }   
+            }
+            UART_MUTEX_UNLOCK();
+            if (retCode) {
+                // UART driver was already working, just return the uart_t structure, syaing that no new driver was installed
+                return uart;
+            }
+            // if we reach this point, it means that we need to restart the UART driver
+            uartEnd(uart_nr);
+        }
+    } else {
+        log_v("UART%d not installed. Starting installation", uart_nr);
+    }
     uart_config_t uart_config;
     uart_config.data_bits = (config & 0xc) >> 2;
     uart_config.parity = (config & 0x3);
@@ -386,7 +490,10 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
     uart_config.baud_rate = baudrate;
     // CLK_APB for ESP32|S2|S3|C3 -- CLK_PLL_F40M for C2 -- CLK_PLL_F48M for H2 -- CLK_PLL_F80M for C6
     uart_config.source_clk = UART_SCLK_DEFAULT;
+
+    UART_MUTEX_LOCK();
     bool retCode = ESP_OK == uart_driver_install(uart_nr, rx_buffer_size, tx_buffer_size, 20, &(uart->uart_event_queue), 0);
+
     if (retCode) retCode &= ESP_OK == uart_param_config(uart_nr, &uart_config);
 
     // Is it right or the idea is to swap rx and tx pins? 
@@ -395,19 +502,31 @@ uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rx
         retCode &= ESP_OK == uart_set_line_inverse(uart_nr, UART_SIGNAL_TXD_INV | UART_SIGNAL_RXD_INV);    
     }
     
+    if (retCode) {
+        uart->_baudrate = baudrate;
+        uart->_config = config;
+        uart->_inverted = inverted;
+        uart->_rxfifo_full_thrhd = rxfifo_full_thrhd;
+        uart->_rx_buffer_size = rx_buffer_size;
+        uart->_tx_buffer_size = tx_buffer_size;
+        uart->_ctsPin = -1;
+        uart->_rtsPin = -1;
+        uart->has_peek = false;
+        uart->peek_byte = 0;
+    }
     UART_MUTEX_UNLOCK();
+
     // uartSetPins detaches previous pins if new ones are used over a previous begin()
     if (retCode) retCode &= uartSetPins(uart_nr, rxPin, txPin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
-
-    if (retCode) uartFlush(uart);
-    else {
+    if (!retCode) {
         uartEnd(uart_nr);
         uart = NULL;
         log_e("UART%d initialization error.", uart->num);
+    } else {
+        uartFlush(uart);
+        log_v("UART%d initialization done.", uart->num);
     }
-
-    log_v("UART%d baud(%ld) Mode(%x) rxPin(%d) txPin(%d)", uart_nr, baudrate, config, rxPin, txPin);
-    return uart;
+    return uart;  // a new driver was installed
 }
 
 // This function code is under testing - for now just keep it here
@@ -658,6 +777,7 @@ void uartSetBaudRate(uart_t* uart, uint32_t baud_rate)
     if(uart_get_sclk_freq(UART_SCLK_DEFAULT, &sclk_freq) == ESP_OK){
         uart_ll_set_baudrate(UART_LL_GET_HW(uart->num), baud_rate, sclk_freq);
     }
+    uart->_baudrate = baud_rate;
     UART_MUTEX_UNLOCK();
 }
 
@@ -1025,3 +1145,4 @@ int uart_send_msg_with_break(uint8_t uartNum, uint8_t *msg, size_t msgSize)
 }
 
 #endif /* SOC_UART_SUPPORTED */
+
diff --git a/cores/esp32/esp32-hal-uart.h b/cores/esp32/esp32-hal-uart.h
index fbb9694c58a..b33c7bc75fe 100644
--- a/cores/esp32/esp32-hal-uart.h
+++ b/cores/esp32/esp32-hal-uart.h
@@ -32,6 +32,7 @@ extern "C" {
 struct uart_struct_t;
 typedef struct uart_struct_t uart_t;
 
+bool _testUartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t rx_buffer_size, uint16_t tx_buffer_size, bool inverted, uint8_t rxfifo_full_thrhd);
 uart_t* uartBegin(uint8_t uart_nr, uint32_t baudrate, uint32_t config, int8_t rxPin, int8_t txPin, uint16_t rx_buffer_size, uint16_t tx_buffer_size, bool inverted, uint8_t rxfifo_full_thrhd);
 void uartEnd(uint8_t uart_num);
 
diff --git a/tests/uart/uart.ino b/tests/uart/uart.ino
index d056dcc1b39..c10dfc58b24 100644
--- a/tests/uart/uart.ino
+++ b/tests/uart/uart.ino
@@ -78,11 +78,11 @@ void start_serial(unsigned long baudrate = 115200) {
 // This function stops all the available test UARTs
 void stop_serial(bool hard_stop = false) {
   #if SOC_UART_NUM >= 2
-    Serial1.end(hard_stop);
+    Serial1.end(/*hard_stop*/);
   #endif
 
   #if SOC_UART_NUM >= 3
-    Serial2.end(hard_stop);
+    Serial2.end(/*hard_stop*/);
   #endif
 }
 
@@ -139,6 +139,19 @@ void task_delayed_msg(void *pvParameters) {
 // This function is automatically called by unity before each test is run
 void setUp(void) {
   start_serial(115200);
+#if SOC_UART_NUM == 2
+  log_d("Setup internal loop-back from and back to Serial1 (UART1) TX >> Serial1 (UART1) RX");
+
+  Serial1.onReceive([]() {onReceive_cb(Serial1);});
+  uart_internal_loopback(1, RX1);
+#elif SOC_UART_NUM == 3
+  log_d("Setup internal loop-back between Serial1 (UART1) <<--->> Serial2 (UART2)");
+
+  Serial1.onReceive([]() {onReceive_cb(Serial1);});
+  Serial2.onReceive([]() {onReceive_cb(Serial2);});
+  uart_internal_loopback(1, RX2);
+  uart_internal_loopback(2, RX1);
+#endif
 }
 
 // This function is automatically called by unity after each test is run
@@ -393,7 +406,7 @@ void disabled_uart_calls_test(void) {
 
 // This test checks if the pins can be changed and if the message can be transmitted and received correctly after the change
 void change_pins_test(void) {
-  stop_serial();
+  //stop_serial();
 
   log_d("Disabling UART loopback");
 
@@ -453,7 +466,7 @@ void auto_baudrate_test(void) {
     selected_serial = &Serial2;
   #endif
 
-  selected_serial->end(false);
+  //selected_serial->end(false);
 
   log_d("Starting delayed task to send message");