diff --git a/cores/esp32/HWCDC.cpp b/cores/esp32/HWCDC.cpp
index 1d8f61a717d..245b73109d9 100644
--- a/cores/esp32/HWCDC.cpp
+++ b/cores/esp32/HWCDC.cpp
@@ -32,11 +32,11 @@
 ESP_EVENT_DEFINE_BASE(ARDUINO_HW_CDC_EVENTS);
 
 static RingbufHandle_t tx_ring_buf = NULL;
-static xQueueHandle rx_queue = NULL;
+static QueueHandle_t rx_queue = NULL;
 static uint8_t rx_data_buf[64] = {0};
 static intr_handle_t intr_handle = NULL;
 static volatile bool initial_empty = false;
-static xSemaphoreHandle tx_lock = NULL;
+static SemaphoreHandle_t tx_lock = NULL;
 
 // workaround for when USB CDC is not connected
 static uint32_t tx_timeout_ms = 0;
diff --git a/cores/esp32/HardwareSerial.cpp b/cores/esp32/HardwareSerial.cpp
index 531dfd28a54..a1fe17c4e5d 100644
--- a/cores/esp32/HardwareSerial.cpp
+++ b/cores/esp32/HardwareSerial.cpp
@@ -298,7 +298,7 @@ void HardwareSerial::_uartEventTask(void *args)
     if (uartEventQueue != NULL) {
         for(;;) {
             //Waiting for UART event.
-            if(xQueueReceive(uartEventQueue, (void * )&event, (portTickType)portMAX_DELAY)) {
+            if(xQueueReceive(uartEventQueue, (void * )&event, (TickType_t)portMAX_DELAY)) {
                 hardwareSerial_error_t currentErr = UART_NO_ERROR;
                 switch(event.type) {
                     case UART_DATA:
diff --git a/cores/esp32/USBCDC.cpp b/cores/esp32/USBCDC.cpp
index df5462884c4..4fd05080501 100644
--- a/cores/esp32/USBCDC.cpp
+++ b/cores/esp32/USBCDC.cpp
@@ -123,7 +123,7 @@ size_t USBCDC::setRxBufferSize(size_t rx_queue_len){
             uxQueueSpacesAvailable(rx_queue) + uxQueueMessagesWaiting(rx_queue) : 0;
 
     if (rx_queue_len != currentQueueSize) {
-        xQueueHandle new_rx_queue = NULL;
+        QueueHandle_t new_rx_queue = NULL;
         if (rx_queue_len) {
             new_rx_queue = xQueueCreate(rx_queue_len, sizeof(uint8_t));
             if(!new_rx_queue){
diff --git a/cores/esp32/USBCDC.h b/cores/esp32/USBCDC.h
index 4012b2b369a..e5d1bb101c5 100644
--- a/cores/esp32/USBCDC.h
+++ b/cores/esp32/USBCDC.h
@@ -135,8 +135,8 @@ class USBCDC: public Stream
     bool     rts;
     bool     connected;
     bool     reboot_enable;
-    xQueueHandle rx_queue;
-    xSemaphoreHandle tx_lock;
+    QueueHandle_t rx_queue;
+    SemaphoreHandle_t tx_lock;
     uint32_t tx_timeout_ms;
     
 };
diff --git a/cores/esp32/esp32-hal-cpu.c b/cores/esp32/esp32-hal-cpu.c
index e1befa1fb33..915a3211d7a 100644
--- a/cores/esp32/esp32-hal-cpu.c
+++ b/cores/esp32/esp32-hal-cpu.c
@@ -60,7 +60,7 @@ typedef struct apb_change_cb_s {
 
 
 static apb_change_t * apb_change_callbacks = NULL;
-static xSemaphoreHandle apb_change_lock = NULL;
+static SemaphoreHandle_t apb_change_lock = NULL;
 
 static void initApbChangeCallback(){
     static volatile bool initialized = false;
diff --git a/cores/esp32/esp32-hal-i2c-slave.c b/cores/esp32/esp32-hal-i2c-slave.c
index a3e863cf799..10629e48f28 100644
--- a/cores/esp32/esp32-hal-i2c-slave.c
+++ b/cores/esp32/esp32-hal-i2c-slave.c
@@ -76,16 +76,16 @@ typedef struct i2c_slave_struct_t {
     void * arg;
     intr_handle_t intr_handle;
     TaskHandle_t task_handle;
-    xQueueHandle event_queue;
+    QueueHandle_t event_queue;
 #if I2C_SLAVE_USE_RX_QUEUE
-    xQueueHandle rx_queue;
+    QueueHandle_t rx_queue;
 #else
     RingbufHandle_t rx_ring_buf;
 #endif
-    xQueueHandle tx_queue;
+    QueueHandle_t tx_queue;
     uint32_t rx_data_count;
 #if !CONFIG_DISABLE_HAL_LOCKS
-    xSemaphoreHandle lock;
+    SemaphoreHandle_t lock;
 #endif
 } i2c_slave_struct_t;
 
@@ -431,7 +431,7 @@ size_t i2cSlaveWrite(uint8_t num, const uint8_t *buf, uint32_t len, uint32_t tim
                 to_queue = len;
             }
             for (size_t i = 0; i < to_queue; i++) {
-                if (xQueueSend(i2c->tx_queue, &buf[i], timeout_ms / portTICK_RATE_MS) != pdTRUE) {
+                if (xQueueSend(i2c->tx_queue, &buf[i], timeout_ms / portTICK_PERIOD_MS) != pdTRUE) {
                     xQueueReset(i2c->tx_queue);
                     to_queue = 0;
                     break;
diff --git a/cores/esp32/esp32-hal-i2c.c b/cores/esp32/esp32-hal-i2c.c
index 84959dbc9a3..4fe09ff3759 100644
--- a/cores/esp32/esp32-hal-i2c.c
+++ b/cores/esp32/esp32-hal-i2c.c
@@ -184,7 +184,7 @@ esp_err_t i2cWrite(uint8_t i2c_num, uint16_t address, const uint8_t* buff, size_
     }
     
     //short implementation does not support zero size writes (example when scanning) PR in IDF?
-    //ret =  i2c_master_write_to_device((i2c_port_t)i2c_num, address, buff, size, timeOutMillis / portTICK_RATE_MS);
+    //ret =  i2c_master_write_to_device((i2c_port_t)i2c_num, address, buff, size, timeOutMillis / portTICK_PERIOD_MS);
 
     ret = ESP_OK;
     uint8_t cmd_buff[I2C_LINK_RECOMMENDED_SIZE(1)] = { 0 };
@@ -207,7 +207,7 @@ esp_err_t i2cWrite(uint8_t i2c_num, uint16_t address, const uint8_t* buff, size_
     if (ret != ESP_OK) {
         goto end;
     }
-    ret = i2c_master_cmd_begin((i2c_port_t)i2c_num, cmd, timeOutMillis / portTICK_RATE_MS);
+    ret = i2c_master_cmd_begin((i2c_port_t)i2c_num, cmd, timeOutMillis / portTICK_PERIOD_MS);
 
 end:
     if(cmd != NULL){
@@ -235,7 +235,7 @@ esp_err_t i2cRead(uint8_t i2c_num, uint16_t address, uint8_t* buff, size_t size,
     if(!bus[i2c_num].initialized){
         log_e("bus is not initialized");
     } else {
-        ret = i2c_master_read_from_device((i2c_port_t)i2c_num, address, buff, size, timeOutMillis / portTICK_RATE_MS);
+        ret = i2c_master_read_from_device((i2c_port_t)i2c_num, address, buff, size, timeOutMillis / portTICK_PERIOD_MS);
         if(ret == ESP_OK){
             *readCount = size;
         } else {
@@ -264,7 +264,7 @@ esp_err_t i2cWriteReadNonStop(uint8_t i2c_num, uint16_t address, const uint8_t*
     if(!bus[i2c_num].initialized){
         log_e("bus is not initialized");
     } else {
-        ret = i2c_master_write_read_device((i2c_port_t)i2c_num, address, wbuff, wsize, rbuff, rsize, timeOutMillis / portTICK_RATE_MS);
+        ret = i2c_master_write_read_device((i2c_port_t)i2c_num, address, wbuff, wsize, rbuff, rsize, timeOutMillis / portTICK_PERIOD_MS);
         if(ret == ESP_OK){
             *readCount = rsize;
         } else {
diff --git a/cores/esp32/esp32-hal-rmt.c b/cores/esp32/esp32-hal-rmt.c
index 9230928aee0..bc31e844178 100644
--- a/cores/esp32/esp32-hal-rmt.c
+++ b/cores/esp32/esp32-hal-rmt.c
@@ -60,7 +60,7 @@ struct rmt_obj_s {
   size_t *num_symbols_read;                  // Pointer to the number of RMT symbol read by IDF RMT RX Done
 
 #if !CONFIG_DISABLE_HAL_LOCKS
-  xSemaphoreHandle g_rmt_objlocks;           // Channel Semaphore Lock
+  SemaphoreHandle_t g_rmt_objlocks;           // Channel Semaphore Lock
 #endif /* CONFIG_DISABLE_HAL_LOCKS */
 };
 
@@ -69,7 +69,7 @@ typedef struct rmt_obj_s *rmt_bus_handle_t;
 /**
    Internal variables used in RMT API
 */
-static xSemaphoreHandle g_rmt_block_lock = NULL;
+static SemaphoreHandle_t g_rmt_block_lock = NULL;
 
 /**
    Internal method (private) declarations
diff --git a/cores/esp32/esp32-hal-spi.c b/cores/esp32/esp32-hal-spi.c
index 4a5515eaeb5..a850e5ea317 100644
--- a/cores/esp32/esp32-hal-spi.c
+++ b/cores/esp32/esp32-hal-spi.c
@@ -59,7 +59,7 @@
 struct spi_struct_t {
     spi_dev_t * dev;
 #if !CONFIG_DISABLE_HAL_LOCKS
-    xSemaphoreHandle lock;
+    SemaphoreHandle_t lock;
 #endif
     uint8_t num;
     int8_t sck;
diff --git a/cores/esp32/esp32-hal-tinyusb.c b/cores/esp32/esp32-hal-tinyusb.c
index eaf9674fa0a..fa97fb8bb41 100644
--- a/cores/esp32/esp32-hal-tinyusb.c
+++ b/cores/esp32/esp32-hal-tinyusb.c
@@ -406,7 +406,7 @@ static void hw_cdc_reset_handler(void *arg) {
     usb_serial_jtag_ll_clr_intsts_mask(usbjtag_intr_status);
     
     if (usbjtag_intr_status & USB_SERIAL_JTAG_INTR_BUS_RESET) {
-        xSemaphoreGiveFromISR((xSemaphoreHandle)arg, &xTaskWoken);
+        xSemaphoreGiveFromISR((SemaphoreHandle_t)arg, &xTaskWoken);
     }
 
     if (xTaskWoken == pdTRUE) {
@@ -441,7 +441,7 @@ static void usb_switch_to_cdc_jtag(){
     usb_serial_jtag_ll_clr_intsts_mask(USB_SERIAL_JTAG_LL_INTR_MASK);
     usb_serial_jtag_ll_ena_intr_mask(USB_SERIAL_JTAG_INTR_BUS_RESET);
     intr_handle_t intr_handle = NULL;
-    xSemaphoreHandle reset_sem = xSemaphoreCreateBinary();
+    SemaphoreHandle_t reset_sem = xSemaphoreCreateBinary();
     if(reset_sem){
         if(esp_intr_alloc(ETS_USB_SERIAL_JTAG_INTR_SOURCE, 0, hw_cdc_reset_handler, reset_sem, &intr_handle) != ESP_OK){
             vSemaphoreDelete(reset_sem);
diff --git a/cores/esp32/esp32-hal-uart.c b/cores/esp32/esp32-hal-uart.c
index 2c0cef66a7b..149c8c40dcd 100644
--- a/cores/esp32/esp32-hal-uart.c
+++ b/cores/esp32/esp32-hal-uart.c
@@ -38,7 +38,7 @@ static int s_uart_debug_nr = 0;
 struct uart_struct_t {
 
 #if !CONFIG_DISABLE_HAL_LOCKS
-    xSemaphoreHandle lock;
+    SemaphoreHandle_t lock;
 #endif
 
     uint8_t num;
@@ -459,7 +459,7 @@ uint8_t uartRead(uart_t* uart)
       c = uart->peek_byte;
     } else {
 
-        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_RATE_MS);
+        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_PERIOD_MS);
         if (len <= 0) { // includes negative return from IDF in case of error
             c  = 0;
         }
@@ -481,7 +481,7 @@ uint8_t uartPeek(uart_t* uart)
     if (uart->has_peek) {
       c = uart->peek_byte;
     } else {
-        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_RATE_MS);
+        int len = uart_read_bytes(uart->num, &c, 1, 20 / portTICK_PERIOD_MS);
         if (len <= 0) { // includes negative return from IDF in case of error
             c  = 0;
         } else {
diff --git a/libraries/AsyncUDP/src/AsyncUDP.cpp b/libraries/AsyncUDP/src/AsyncUDP.cpp
index 92f9e2a827b..e533755da7a 100644
--- a/libraries/AsyncUDP/src/AsyncUDP.cpp
+++ b/libraries/AsyncUDP/src/AsyncUDP.cpp
@@ -145,7 +145,7 @@ typedef struct {
         struct netif * netif;
 } lwip_event_packet_t;
 
-static xQueueHandle _udp_queue;
+static QueueHandle_t _udp_queue;
 static volatile TaskHandle_t _udp_task_handle = NULL;
 
 static void _udp_task(void *pvParameters){
diff --git a/libraries/AsyncUDP/src/AsyncUDP.h b/libraries/AsyncUDP/src/AsyncUDP.h
index 963a67e3a6c..c9f365d1197 100644
--- a/libraries/AsyncUDP/src/AsyncUDP.h
+++ b/libraries/AsyncUDP/src/AsyncUDP.h
@@ -104,7 +104,7 @@ class AsyncUDP : public Print
 {
 protected:
     udp_pcb *_pcb;
-    //xSemaphoreHandle _lock;
+    //SemaphoreHandle_t _lock;
     bool _connected;
 	esp_err_t _lastErr;
     AuPacketHandlerFunction _handler;
diff --git a/libraries/BluetoothSerial/src/BluetoothSerial.cpp b/libraries/BluetoothSerial/src/BluetoothSerial.cpp
index 3a456847b8b..52254437923 100644
--- a/libraries/BluetoothSerial/src/BluetoothSerial.cpp
+++ b/libraries/BluetoothSerial/src/BluetoothSerial.cpp
@@ -47,8 +47,8 @@ const char * _spp_server_name = "ESP32SPP";
 #define SPP_CONGESTED_TIMEOUT 1000
 
 static uint32_t _spp_client = 0;
-static xQueueHandle _spp_rx_queue = NULL;
-static xQueueHandle _spp_tx_queue = NULL;
+static QueueHandle_t _spp_rx_queue = NULL;
+static QueueHandle_t _spp_tx_queue = NULL;
 static SemaphoreHandle_t _spp_tx_done = NULL;
 static TaskHandle_t _spp_task_handle = NULL;
 static EventGroupHandle_t _spp_event_group = NULL;
diff --git a/libraries/USB/examples/CustomHIDDevice/CustomHIDDevice.ino b/libraries/USB/examples/CustomHIDDevice/CustomHIDDevice.ino
index 3644b167fed..bbc7bdef7eb 100644
--- a/libraries/USB/examples/CustomHIDDevice/CustomHIDDevice.ino
+++ b/libraries/USB/examples/CustomHIDDevice/CustomHIDDevice.ino
@@ -1,11 +1,11 @@
 #if ARDUINO_USB_MODE
-#warning This sketch should be used when USB is in OTG mode
-void setup(){}
-void loop(){}
+  #warning This sketch should be used when USB is in OTG mode
+  void setup(){}
+  void loop(){}
 #else
-#include "USB.h"
-#include "USBHID.h"
-USBHID HID;
+  #include "USB.h"
+  #include "USBHID.h"
+  USBHID HID;
 
 static const uint8_t report_descriptor[] = { // 8 axis
     0x05, 0x01,        // Usage Page (Generic Desktop Ctrls)
@@ -55,7 +55,6 @@ public:
 };
 
 CustomHIDDevice Device;
-#endif /* ARDUINO_USB_MODE */
 
 const int buttonPin = 0;
 int previousButtonState = HIGH;
@@ -83,3 +82,4 @@ void loop() {
     delay(100);
   }
 }
+#endif /* ARDUINO_USB_MODE */
\ No newline at end of file
diff --git a/libraries/USB/src/USBHID.cpp b/libraries/USB/src/USBHID.cpp
index ee673d174c1..2e28bb8d159 100644
--- a/libraries/USB/src/USBHID.cpp
+++ b/libraries/USB/src/USBHID.cpp
@@ -36,8 +36,8 @@ static tinyusb_hid_device_t tinyusb_hid_devices[USB_HID_DEVICES_MAX];
 
 static uint8_t tinyusb_hid_devices_num = 0;
 static bool tinyusb_hid_devices_is_initialized = false;
-static xSemaphoreHandle tinyusb_hid_device_input_sem = NULL;
-static xSemaphoreHandle tinyusb_hid_device_input_mutex = NULL;
+static SemaphoreHandle_t tinyusb_hid_device_input_sem = NULL;
+static SemaphoreHandle_t tinyusb_hid_device_input_mutex = NULL;
 
 static bool tinyusb_hid_is_initialized = false;
 static uint8_t tinyusb_loaded_hid_devices_num = 0;
diff --git a/libraries/USB/src/USBHIDVendor.cpp b/libraries/USB/src/USBHIDVendor.cpp
index 342c47f96db..5eab6571d7e 100644
--- a/libraries/USB/src/USBHIDVendor.cpp
+++ b/libraries/USB/src/USBHIDVendor.cpp
@@ -60,7 +60,7 @@ esp_err_t arduino_usb_event_handler_register_with(esp_event_base_t event_base, i
 // max size is 64 and we need one byte for the report ID
 static uint8_t HID_VENDOR_REPORT_SIZE = 63;
 static uint8_t feature[64];
-static xQueueHandle rx_queue = NULL;
+static QueueHandle_t rx_queue = NULL;
 static bool prepend_size = false;
 
 USBHIDVendor::USBHIDVendor(uint8_t report_size, bool prepend): hid(){
diff --git a/libraries/USB/src/USBVendor.cpp b/libraries/USB/src/USBVendor.cpp
index dabc5a0766d..da3d0e18653 100644
--- a/libraries/USB/src/USBVendor.cpp
+++ b/libraries/USB/src/USBVendor.cpp
@@ -23,7 +23,7 @@ esp_err_t arduino_usb_event_post(esp_event_base_t event_base, int32_t event_id,
 esp_err_t arduino_usb_event_handler_register_with(esp_event_base_t event_base, int32_t event_id, esp_event_handler_t event_handler, void *event_handler_arg);
 
 static USBVendor * _Vendor = NULL;
-static xQueueHandle rx_queue = NULL;
+static QueueHandle_t rx_queue = NULL;
 static uint8_t USB_VENDOR_ENDPOINT_SIZE = 64;
 
 uint16_t tusb_vendor_load_descriptor(uint8_t * dst, uint8_t * itf)
diff --git a/libraries/Update/examples/AWS_S3_OTA_Update/StartCounter.ino.bin b/libraries/Update/examples/AWS_S3_OTA_Update/StartCounter.ino.bin
index 14732a0adb1..4892698815c 100644
Binary files a/libraries/Update/examples/AWS_S3_OTA_Update/StartCounter.ino.bin and b/libraries/Update/examples/AWS_S3_OTA_Update/StartCounter.ino.bin differ
diff --git a/libraries/WiFi/examples/FTM/FTM_Initiator/FTM_Initiator.ino b/libraries/WiFi/examples/FTM/FTM_Initiator/FTM_Initiator.ino
index 6cc8659e3e2..eac6563fc95 100644
--- a/libraries/WiFi/examples/FTM/FTM_Initiator/FTM_Initiator.ino
+++ b/libraries/WiFi/examples/FTM/FTM_Initiator/FTM_Initiator.ino
@@ -23,7 +23,7 @@ const uint8_t FTM_FRAME_COUNT = 16;
 const uint16_t FTM_BURST_PERIOD = 2;
 
 // Semaphore to signal when FTM Report has been received
-xSemaphoreHandle ftmSemaphore;
+SemaphoreHandle_t ftmSemaphore;
 // Status of the received FTM Report
 bool ftmSuccess = true;
 
diff --git a/libraries/WiFi/src/WiFiGeneric.cpp b/libraries/WiFi/src/WiFiGeneric.cpp
index e91f3479ff2..7c8629b3c45 100644
--- a/libraries/WiFi/src/WiFiGeneric.cpp
+++ b/libraries/WiFi/src/WiFiGeneric.cpp
@@ -296,7 +296,7 @@ static void set_esp_netif_hostname(const char * name){
 	}
 }
 
-static xQueueHandle _arduino_event_queue;
+static QueueHandle_t _arduino_event_queue;
 static TaskHandle_t _arduino_event_task_handle = NULL;
 static EventGroupHandle_t _arduino_event_group = NULL;