فهرست منبع

freertos: Remove legacy data types

This commit removes the usage of all legacy FreeRTOS data types that
are exposed via configENABLE_BACKWARD_COMPATIBILITY. Legacy types can
still be used by enabling CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY.
Darian Leung 4 سال پیش
والد
کامیت
57fd78f5ba
100فایلهای تغییر یافته به همراه480 افزوده شده و 533 حذف شده
  1. 1 1
      components/bt/common/osi/include/osi/mutex.h
  2. 1 1
      components/bt/common/osi/include/osi/semaphore.h
  3. 1 1
      components/bt/common/osi/thread.c
  4. 2 2
      components/driver/adc.c
  5. 1 1
      components/driver/esp32/touch_sensor.c
  6. 7 7
      components/driver/i2c.c
  7. 8 8
      components/driver/i2s.c
  8. 2 2
      components/driver/ledc.c
  9. 1 1
      components/driver/rmt.c
  10. 7 7
      components/driver/test/adc_dma_test/test_esp32s2.c
  11. 2 2
      components/driver/test/dac_dma_test/test_esp32s2.c
  12. 1 1
      components/driver/test/test_adc2_with_wifi.c
  13. 16 16
      components/driver/test/test_adc_common.c
  14. 5 5
      components/driver/test/test_dac.c
  15. 38 38
      components/driver/test/test_gpio.c
  16. 17 17
      components/driver/test/test_i2c.c
  17. 2 2
      components/driver/test/test_i2s.c
  18. 17 17
      components/driver/test/test_ledc.c
  19. 14 14
      components/driver/test/test_pcnt.c
  20. 2 2
      components/driver/test/test_rs485.c
  21. 10 10
      components/driver/test/test_rtcio.c
  22. 8 8
      components/driver/test/test_uart.c
  23. 4 4
      components/driver/test/touch_sensor_test/test_touch_v2.c
  24. 12 12
      components/driver/test_apps/gptimer/main/test_gptimer.c
  25. 11 11
      components/driver/uart.c
  26. 6 14
      components/driver/usb_serial_jtag.c
  27. 2 2
      components/efuse/test/test_efuse.c
  28. 2 2
      components/esp_gdbstub/src/gdbstub.c
  29. 7 15
      components/esp_hid/private/esp_hidh_private.h
  30. 1 1
      components/esp_hid/src/ble_hidd.c
  31. 6 14
      components/esp_hid/src/ble_hidh.c
  32. 1 1
      components/esp_hid/src/esp_hidh.c
  33. 2 2
      components/esp_http_server/src/port/esp32/osal.h
  34. 11 11
      components/esp_hw_support/test/test_dport.c
  35. 1 1
      components/esp_hw_support/test/test_intr_alloc.c
  36. 6 14
      components/esp_netif/esp_netif_objects.c
  37. 1 1
      components/esp_ringbuf/test/test_ringbuf.c
  38. 2 2
      components/esp_system/port/arch/xtensa/panic_arch.c
  39. 2 2
      components/esp_system/task_wdt.c
  40. 6 6
      components/esp_system/test/test_ipc.c
  41. 3 3
      components/esp_system/test/test_ipc_isr.c
  42. 2 2
      components/esp_system/test/test_sleep.c
  43. 3 3
      components/esp_websocket_client/esp_websocket_client.c
  44. 4 4
      components/esp_wifi/src/smartconfig_ack.c
  45. 3 3
      components/esp_wifi/test/test_wifi.c
  46. 6 14
      components/espcoredump/src/core_dump_elf.c
  47. 3 3
      components/espcoredump/test_apps/main/test_core_dump.c
  48. 3 3
      components/freemodbus/port/portevent.c
  49. 5 5
      components/freemodbus/tcp_slave/port/port_tcp_slave.c
  50. 2 2
      components/freemodbus/tcp_slave/port/port_tcp_slave.h
  51. 1 1
      components/freertos/FreeRTOS-Kernel/portable/xtensa/port.c
  52. 7 0
      components/freertos/Kconfig
  53. 6 0
      components/freertos/esp_additions/include/freertos/FreeRTOSConfig.h
  54. 6 1
      components/freertos/test/test_spinlocks.c
  55. 2 2
      components/lwip/port/esp32/freertos/sys_arch.c
  56. 1 1
      components/mbedtls/test/test_aes.c
  57. 1 1
      components/mbedtls/test/test_aes_sha_parallel.c
  58. 10 10
      components/mbedtls/test/test_aes_sha_rsa.c
  59. 2 2
      components/mbedtls/test/test_esp_crt_bundle.c
  60. 3 3
      components/mbedtls/test/test_mbedtls_sha.c
  61. 5 17
      components/mdns/host_test/components/freertos_linux/include/freertos/FreeRTOS.h
  62. 6 14
      components/mdns/host_test/components/freertos_linux/include/freertos/task.h
  63. 19 19
      components/mdns/mdns.c
  64. 1 1
      components/mdns/private_include/mdns_private.h
  65. 2 5
      components/mdns/test_afl_fuzz_host/esp32_mock.h
  66. 6 6
      components/newlib/locks.c
  67. 8 8
      components/newlib/test/test_time.c
  68. 7 15
      components/protocomm/src/transports/protocomm_console.c
  69. 2 2
      components/pthread/pthread.c
  70. 1 1
      components/tinyusb/additions/src/tusb_cdc_acm.c
  71. 1 1
      components/vfs/test/test_vfs_eventfd.c
  72. 7 15
      components/vfs/test/test_vfs_select.c
  73. 6 6
      components/wpa_supplicant/test/test_offchannel.c
  74. 2 2
      docs/en/api-guides/SYSVIEW_FreeRTOS.txt
  75. 1 1
      docs/en/api-reference/protocols/modbus.rst
  76. 1 1
      docs/en/api-reference/system/freertos_additions.rst
  77. 8 0
      docs/en/migration-guides/freertos.rst
  78. 2 2
      docs/zh_CN/api-guides/SYSVIEW_FreeRTOS.txt
  79. 4 4
      examples/bluetooth/bluedroid/ble/ble_spp_client/main/spp_client_demo.c
  80. 4 4
      examples/bluetooth/bluedroid/ble/ble_spp_server/main/ble_spp_server_demo.c
  81. 2 2
      examples/bluetooth/bluedroid/classic_bt/a2dp_sink/main/bt_app_av.c
  82. 7 7
      examples/bluetooth/bluedroid/classic_bt/a2dp_sink/main/bt_app_core.c
  83. 4 4
      examples/bluetooth/bluedroid/classic_bt/a2dp_source/main/bt_app_core.c
  84. 1 1
      examples/bluetooth/bluedroid/classic_bt/a2dp_source/main/main.c
  85. 2 2
      examples/bluetooth/bluedroid/classic_bt/bt_hid_mouse_device/main/main.c
  86. 2 2
      examples/bluetooth/bluedroid/classic_bt/bt_spp_initiator/main/console_uart.c
  87. 5 5
      examples/bluetooth/bluedroid/classic_bt/bt_spp_vfs_acceptor/main/spp_task.c
  88. 5 5
      examples/bluetooth/bluedroid/classic_bt/bt_spp_vfs_initiator/main/spp_task.c
  89. 5 5
      examples/bluetooth/bluedroid/classic_bt/hfp_ag/main/bt_app_core.c
  90. 4 4
      examples/bluetooth/bluedroid/classic_bt/hfp_ag/main/bt_app_hf.c
  91. 5 5
      examples/bluetooth/bluedroid/classic_bt/hfp_hf/main/bt_app_core.c
  92. 3 3
      examples/bluetooth/bluedroid/coex/a2dp_gatts_coex/main/bt_app_av.c
  93. 8 8
      examples/bluetooth/bluedroid/coex/a2dp_gatts_coex/main/bt_app_core.c
  94. 4 4
      examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/run_tc.c
  95. 2 2
      examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/run_tc.h
  96. 2 2
      examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/sync.c
  97. 1 1
      examples/bluetooth/esp_ble_mesh/ble_mesh_console/main/ble_mesh_adapter.h
  98. 2 2
      examples/bluetooth/esp_ble_mesh/ble_mesh_console/main/transaction.c
  99. 1 1
      examples/bluetooth/esp_ble_mesh/ble_mesh_node/onoff_client/tutorial/BLE_Mesh_Node_OnOff_Client_Example_Walkthrough.md
  100. 3 3
      examples/bluetooth/esp_ble_mesh/ble_mesh_wifi_coexist/main/cmd_wifi.c

+ 1 - 1
components/bt/common/osi/include/osi/mutex.h

@@ -30,7 +30,7 @@
 #define osi_mutex_valid( x ) ( ( ( *x ) == NULL) ? pdFALSE : pdTRUE )
 #define osi_mutex_set_invalid( x ) ( ( *x ) = NULL )
 
-typedef xSemaphoreHandle osi_mutex_t;
+typedef SemaphoreHandle_t osi_mutex_t;
 
 int osi_mutex_new(osi_mutex_t *mutex);
 

+ 1 - 1
components/bt/common/osi/include/osi/semaphore.h

@@ -26,7 +26,7 @@
 
 #define OSI_SEM_MAX_TIMEOUT 0xffffffffUL
 
-typedef xSemaphoreHandle osi_sem_t;
+typedef SemaphoreHandle_t osi_sem_t;
 
 #define osi_sem_valid( x ) ( ( ( *x ) == NULL) ? pdFALSE : pdTRUE )
 #define osi_sem_set_invalid( x ) ( ( *x ) = NULL )

+ 1 - 1
components/bt/common/osi/thread.c

@@ -264,7 +264,7 @@ const char *osi_thread_name(osi_thread_t *thread)
 {
     assert(thread != NULL);
 
-    return pcTaskGetTaskName(thread->thread_handle);
+    return pcTaskGetName(thread->thread_handle);
 }
 
 int osi_thread_queue_wait_size(osi_thread_t *thread, int wq_idx)

+ 2 - 2
components/driver/adc.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2016-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2016-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -479,7 +479,7 @@ esp_err_t adc_digi_read_bytes(uint8_t *buf, uint32_t length_max, uint32_t *out_l
     uint8_t *data = NULL;
     size_t size = 0;
 
-    ticks_to_wait = timeout_ms / portTICK_RATE_MS;
+    ticks_to_wait = timeout_ms / portTICK_PERIOD_MS;
     if (timeout_ms == ADC_MAX_DELAY) {
         ticks_to_wait = portMAX_DELAY;
     }

+ 1 - 1
components/driver/esp32/touch_sensor.c

@@ -272,7 +272,7 @@ esp_err_t touch_pad_config(touch_pad_t touch_num, uint16_t threshold)
         //If the FSM mode is 'TOUCH_FSM_MODE_TIMER', The data will be ready after one measurement cycle
         //after this function is executed, otherwise, the "touch_value" by "touch_pad_read" is 0.
         wait_time_ms = sleep_time / (rtc_clk / 1000) + meas_cycle / (RTC_FAST_CLK_FREQ_APPROX / 1000);
-        wait_tick = wait_time_ms / portTICK_RATE_MS;
+        wait_tick = wait_time_ms / portTICK_PERIOD_MS;
         vTaskDelay(wait_tick ? wait_tick : 1);
         s_touch_pad_init_bit |= (1 << touch_num);
     } else {

+ 7 - 7
components/driver/i2c.c

@@ -153,13 +153,13 @@ typedef struct {
     int intr_alloc_flags;            /*!< Used to allocate the interrupt */
     StaticQueue_t evt_queue_buffer;  /*!< The buffer that will hold the queue structure*/
 #endif
-    xSemaphoreHandle cmd_mux;        /*!< semaphore to lock command process */
+    SemaphoreHandle_t cmd_mux;        /*!< semaphore to lock command process */
 #ifdef CONFIG_PM_ENABLE
     esp_pm_lock_handle_t pm_lock;
 #endif
 
-    xSemaphoreHandle slv_rx_mux;     /*!< slave rx buffer mux */
-    xSemaphoreHandle slv_tx_mux;     /*!< slave tx buffer mux */
+    SemaphoreHandle_t slv_rx_mux;     /*!< slave rx buffer mux */
+    SemaphoreHandle_t slv_tx_mux;     /*!< slave tx buffer mux */
     size_t rx_buf_length;            /*!< rx buffer length */
     RingbufHandle_t rx_ring_buf;     /*!< rx ringbuffer handler of slave mode */
     size_t tx_buf_length;            /*!< tx buffer length */
@@ -1403,7 +1403,7 @@ esp_err_t i2c_master_cmd_begin(i2c_port_t i2c_num, i2c_cmd_handle_t cmd_handle,
     static uint8_t clear_bus_cnt = 0;
     esp_err_t ret = ESP_FAIL;
     i2c_obj_t *p_i2c = p_i2c_obj[i2c_num];
-    portTickType ticks_start = xTaskGetTickCount();
+    TickType_t ticks_start = xTaskGetTickCount();
     portBASE_TYPE res = xSemaphoreTake(p_i2c->cmd_mux, ticks_to_wait);
     if (res == pdFALSE) {
         return ESP_ERR_TIMEOUT;
@@ -1503,7 +1503,7 @@ int i2c_slave_write_buffer(i2c_port_t i2c_num, const uint8_t *data, int size, Ti
 
     portBASE_TYPE res;
     int cnt = 0;
-    portTickType ticks_end = xTaskGetTickCount() + ticks_to_wait;
+    TickType_t ticks_end = xTaskGetTickCount() + ticks_to_wait;
 
     res = xSemaphoreTake(p_i2c->slv_tx_mux, ticks_to_wait);
     if (res == pdFALSE) {
@@ -1536,8 +1536,8 @@ int i2c_slave_read_buffer(i2c_port_t i2c_num, uint8_t *data, size_t max_size, Ti
     if (xSemaphoreTake(p_i2c->slv_rx_mux, ticks_to_wait) == pdFALSE) {
         return 0;
     }
-    portTickType ticks_rem = ticks_to_wait;
-    portTickType ticks_end = xTaskGetTickCount() + ticks_to_wait;
+    TickType_t ticks_rem = ticks_to_wait;
+    TickType_t ticks_end = xTaskGetTickCount() + ticks_to_wait;
     I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
     i2c_hal_enable_slave_rx_it(&(i2c_context[i2c_num].hal));
     I2C_EXIT_CRITICAL(&(i2c_context[i2c_num].spinlock));

+ 8 - 8
components/driver/i2s.c

@@ -70,7 +70,7 @@ typedef struct {
     volatile int rw_pos;
     volatile void *curr_ptr;
     SemaphoreHandle_t mux;
-    xQueueHandle queue;
+    QueueHandle_t queue;
     lldesc_t **desc;
 } i2s_dma_t;
 
@@ -1568,12 +1568,12 @@ esp_err_t i2s_set_clk(i2s_port_t i2s_num, uint32_t rate, uint32_t bits_cfg, i2s_
         cfg->total_chan = 2;
 #endif
         if (cfg->mode & I2S_MODE_TX) {
-            xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (portTickType)portMAX_DELAY);
+            xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (TickType_t)portMAX_DELAY);
             i2s_hal_tx_set_channel_style(&(p_i2s[i2s_num]->hal), cfg);
             xSemaphoreGive(p_i2s[i2s_num]->tx->mux);
         }
         if (cfg->mode & I2S_MODE_RX) {
-            xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (portTickType)portMAX_DELAY);
+            xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (TickType_t)portMAX_DELAY);
             i2s_hal_rx_set_channel_style(&(p_i2s[i2s_num]->hal), cfg);
             xSemaphoreGive(p_i2s[i2s_num]->rx->mux);
         }
@@ -1598,7 +1598,7 @@ esp_err_t i2s_set_clk(i2s_port_t i2s_num, uint32_t rate, uint32_t bits_cfg, i2s_
     if (cfg->mode & I2S_MODE_TX) {
         ESP_RETURN_ON_FALSE(p_i2s[i2s_num]->tx, ESP_ERR_INVALID_ARG, TAG, "I2S TX DMA object has not initialized yet");
         /* Waiting for transmit finish */
-        xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (portTickType)portMAX_DELAY);
+        xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (TickType_t)portMAX_DELAY);
         i2s_tx_set_clk_and_channel(i2s_num, &clk_cfg);
         /* If buffer size changed, the DMA buffer need realloc */
         if (need_realloc) {
@@ -1618,7 +1618,7 @@ esp_err_t i2s_set_clk(i2s_port_t i2s_num, uint32_t rate, uint32_t bits_cfg, i2s_
     if (cfg->mode & I2S_MODE_RX) {
         ESP_RETURN_ON_FALSE(p_i2s[i2s_num]->rx, ESP_ERR_INVALID_ARG, TAG, "I2S TX DMA object has not initialized yet");
         /* Waiting for receive finish */
-        xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (portTickType)portMAX_DELAY);
+        xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (TickType_t)portMAX_DELAY);
         i2s_rx_set_clk_and_channel(i2s_num, &clk_cfg);
         /* If buffer size changed, the DMA buffer need realloc */
         if (need_realloc) {
@@ -2012,7 +2012,7 @@ esp_err_t i2s_write(i2s_port_t i2s_num, const void *src, size_t size, size_t *by
     *bytes_written = 0;
     ESP_RETURN_ON_FALSE((i2s_num < I2S_NUM_MAX), ESP_ERR_INVALID_ARG, TAG, "i2s_num error");
     ESP_RETURN_ON_FALSE((p_i2s[i2s_num]->tx), ESP_ERR_INVALID_ARG, TAG, "TX mode is not enabled");
-    xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (TickType_t)portMAX_DELAY);
 #ifdef CONFIG_PM_ENABLE
     esp_pm_lock_acquire(p_i2s[i2s_num]->pm_lock);
 #endif
@@ -2094,7 +2094,7 @@ esp_err_t i2s_write_expand(i2s_port_t i2s_num, const void *src, size_t size, siz
     src_bytes = src_bits / 8;
     aim_bytes = aim_bits / 8;
     zero_bytes = aim_bytes - src_bytes;
-    xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_i2s[i2s_num]->tx->mux, (TickType_t)portMAX_DELAY);
     size = size * aim_bytes / src_bytes;
     ESP_LOGD(TAG, "aim_bytes %d src_bytes %d size %d", aim_bytes, src_bytes, size);
     while (size > 0) {
@@ -2148,7 +2148,7 @@ esp_err_t i2s_read(i2s_port_t i2s_num, void *dest, size_t size, size_t *bytes_re
     dest_byte = (char *)dest;
     ESP_RETURN_ON_FALSE((i2s_num < I2S_NUM_MAX), ESP_ERR_INVALID_ARG, TAG, "i2s_num error");
     ESP_RETURN_ON_FALSE((p_i2s[i2s_num]->rx), ESP_ERR_INVALID_ARG, TAG, "RX mode is not enabled");
-    xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_i2s[i2s_num]->rx->mux, (TickType_t)portMAX_DELAY);
 #ifdef CONFIG_PM_ENABLE
     esp_pm_lock_acquire(p_i2s[i2s_num]->pm_lock);
 #endif

+ 2 - 2
components/driver/ledc.c

@@ -40,8 +40,8 @@ typedef struct {
     int cycle_num;
     int scale;
     ledc_fade_mode_t mode;
-    xSemaphoreHandle ledc_fade_sem;
-    xSemaphoreHandle ledc_fade_mux;
+    SemaphoreHandle_t ledc_fade_sem;
+    SemaphoreHandle_t ledc_fade_mux;
 #if CONFIG_SPIRAM_USE_MALLOC
     StaticQueue_t ledc_fade_sem_storage;
 #endif

+ 1 - 1
components/driver/rmt.c

@@ -77,7 +77,7 @@ typedef struct {
     bool loop_autostop; // mark whether loop auto-stop is enabled
     rmt_channel_t channel;
     const rmt_item32_t *tx_data;
-    xSemaphoreHandle tx_sem;
+    SemaphoreHandle_t tx_sem;
 #if CONFIG_SPIRAM_USE_MALLOC
     int intr_alloc_flags;
     StaticSemaphore_t tx_sem_buffer;

+ 7 - 7
components/driver/test/adc_dma_test/test_esp32s2.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -269,7 +269,7 @@ static esp_err_t adc_dma_data_multi_st_check(adc_unit_t adc, void *dma_addr, uin
     }
     TEST_ESP_OK( adc_digi_start() );
     while (1) {
-        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_RATE_MS), pdTRUE );
+        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_PERIOD_MS), pdTRUE );
         if (evt.int_msk & SPI_IN_SUC_EOF_INT_ENA) {
             break;
         }
@@ -285,7 +285,7 @@ static esp_err_t adc_dma_data_multi_st_check(adc_unit_t adc, void *dma_addr, uin
     }
     TEST_ESP_OK( adc_digi_start() );
     while (1) {
-        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_RATE_MS), pdTRUE );
+        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_PERIOD_MS), pdTRUE );
         if (evt.int_msk & SPI_IN_SUC_EOF_INT_ENA) {
             break;
         }
@@ -301,7 +301,7 @@ static esp_err_t adc_dma_data_multi_st_check(adc_unit_t adc, void *dma_addr, uin
     }
     TEST_ESP_OK( adc_digi_start() );
     while (1) {
-        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_RATE_MS), pdTRUE );
+        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_PERIOD_MS), pdTRUE );
         if (evt.int_msk & SPI_IN_SUC_EOF_INT_ENA) {
             break;
         }
@@ -317,7 +317,7 @@ static esp_err_t adc_dma_data_multi_st_check(adc_unit_t adc, void *dma_addr, uin
     }
     TEST_ESP_OK( adc_digi_start() );
     while (1) {
-        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_RATE_MS), pdTRUE );
+        TEST_ASSERT_EQUAL( xQueueReceive(que_adc, &evt, SAR_SIMPLE_TIMEOUT_MS / portTICK_PERIOD_MS), pdTRUE );
         if (evt.int_msk & SPI_IN_SUC_EOF_INT_ENA) {
             break;
         }
@@ -460,7 +460,7 @@ int test_adc_dig_dma_single_unit(adc_unit_t adc)
     adc_dac_dma_linker_deinit();
     adc_dac_dma_isr_deregister(adc_dma_isr, NULL);
     TEST_ESP_OK( adc_digi_deinit() );
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 
     return 0;
 }
@@ -601,7 +601,7 @@ static void scope_output(int adc_num, int channel, int data)
     }
     if (i == adc_test_num) {
         test_tp_print_to_scope(scope_temp, adc_test_num);
-        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
         for (int i = 0; i < adc_test_num; i++) {
             scope_temp[i] = 0;
         }

+ 2 - 2
components/driver/test/dac_dma_test/test_esp32s2.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -182,7 +182,7 @@ void test_dac_dig_dma_intr_check(dac_digi_convert_mode_t mode)
 
     /* Check interrupt type */
     while (int_mask) {
-        TEST_ASSERT_EQUAL( xQueueReceive(que_dac, &evt, 2000 / portTICK_RATE_MS), pdTRUE );
+        TEST_ASSERT_EQUAL( xQueueReceive(que_dac, &evt, 2000 / portTICK_PERIOD_MS), pdTRUE );
         ESP_LOGI(TAG, "DAC-DMA intr type 0x%x", evt.int_msk);
         if (evt.int_msk & int_mask) {
             int_mask &= (~evt.int_msk);

+ 1 - 1
components/driver/test/test_adc2_with_wifi.c

@@ -251,7 +251,7 @@ static void i2s_adc_test(void)
             } else {
                 gpio_set_pull_mode(ADC1_CHANNEL_4_IO, GPIO_PULLUP_ONLY);
             }
-            vTaskDelay(200 / portTICK_RATE_MS);
+            vTaskDelay(200 / portTICK_PERIOD_MS);
             // read data from adc, will block until buffer is full
             i2s_read(I2S_NUM_0, (void *)i2sReadBuffer, 1024 * sizeof(uint16_t), &bytesRead, portMAX_DELAY);
 

+ 16 - 16
components/driver/test/test_adc_common.c

@@ -87,7 +87,7 @@ void adc_fake_tie_middle(adc_unit_t adc_unit, adc_channel_t channel)
         TEST_ESP_OK(gpio_set_pull_mode(gpio_num, GPIO_PULLUP_PULLDOWN));
         TEST_ESP_OK(rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_DISABLED));
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 }
 
 void adc_fake_tie_high(adc_unit_t adc_unit, adc_channel_t channel)
@@ -111,7 +111,7 @@ void adc_fake_tie_high(adc_unit_t adc_unit, adc_channel_t channel)
         TEST_ESP_OK(rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_OUTPUT_ONLY));
         TEST_ESP_OK(rtc_gpio_set_level(gpio_num, 1));
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 }
 
 void adc_fake_tie_low(adc_unit_t adc_unit, adc_channel_t channel)
@@ -135,7 +135,7 @@ void adc_fake_tie_low(adc_unit_t adc_unit, adc_channel_t channel)
         TEST_ESP_OK(rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_OUTPUT_ONLY));
         TEST_ESP_OK(rtc_gpio_set_level(gpio_num, 0));
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 }
 
 void adc_io_normal(adc_unit_t adc_unit, adc_channel_t channel)
@@ -157,7 +157,7 @@ void adc_io_normal(adc_unit_t adc_unit, adc_channel_t channel)
         TEST_ESP_OK(gpio_set_pull_mode(gpio_num, GPIO_FLOATING));
         TEST_ESP_OK(rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_DISABLED));
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 }
 
 TEST_CASE("ADC1 rtc read", "[adc1]")
@@ -172,7 +172,7 @@ TEST_CASE("ADC1 rtc read", "[adc1]")
         ESP_LOGI(TAG, "[CH%d - IO%d]:", adc1_ch[i], ADC_GET_IO_NUM(0, adc1_ch[i]));
     }
     printf("ADC tie normal read: ");
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 
     /* adc Read */
     printf("ADC1: ");
@@ -187,7 +187,7 @@ TEST_CASE("ADC1 rtc read", "[adc1]")
         adc_fake_tie_high(ADC_UNIT_1, adc1_ch[i]);
     }
     printf("ADC tie high read: ");
-    vTaskDelay(50 / portTICK_RATE_MS);
+    vTaskDelay(50 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC1: ");
     for (int i = 0; i < ADC1_TEST_CHANNEL_NUM; i++) {
@@ -204,7 +204,7 @@ TEST_CASE("ADC1 rtc read", "[adc1]")
         adc_fake_tie_low(ADC_UNIT_1, adc1_ch[i]);
     }
     printf("ADC tie low  read: ");
-    vTaskDelay(50 / portTICK_RATE_MS);
+    vTaskDelay(50 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC1: ");
     for (int i = 0; i < ADC1_TEST_CHANNEL_NUM; i++) {
@@ -221,7 +221,7 @@ TEST_CASE("ADC1 rtc read", "[adc1]")
         adc_fake_tie_middle(ADC_UNIT_1, adc1_ch[i]);
     }
     printf("ADC tie mid  read: ");
-    vTaskDelay(50 / portTICK_RATE_MS);
+    vTaskDelay(50 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC1: ");
     for (int i = 0; i < ADC1_TEST_CHANNEL_NUM; i++) {
@@ -250,7 +250,7 @@ TEST_CASE("ADC2 rtc read", "[adc2]")
         ESP_LOGI(TAG, "[CH%d - IO%d]:", adc2_ch[i], ADC_GET_IO_NUM(1, adc2_ch[i]));
     }
     printf("ADC float read: ");
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 
     /* adc Read */
     printf("ADC2: ");
@@ -265,7 +265,7 @@ TEST_CASE("ADC2 rtc read", "[adc2]")
         adc_fake_tie_high(ADC_UNIT_2, adc2_ch[i]);
     }
     printf("ADC tie high read: ");
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC2: ");
     for (int i = 0; i < ADC2_TEST_CHANNEL_NUM; i++) {
@@ -282,7 +282,7 @@ TEST_CASE("ADC2 rtc read", "[adc2]")
         adc_fake_tie_low(ADC_UNIT_2, adc2_ch[i]);
     }
     printf("ADC tie low read: ");
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC2: ");
     for (int i = 0; i < ADC2_TEST_CHANNEL_NUM; i++) {
@@ -299,7 +299,7 @@ TEST_CASE("ADC2 rtc read", "[adc2]")
         adc_fake_tie_middle(ADC_UNIT_2, adc2_ch[i]);
     }
     printf("ADC tie middle read: ");
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
     /* adc Read */
     printf("ADC2: ");
     for (int i = 0; i < ADC2_TEST_CHANNEL_NUM; i++) {
@@ -352,7 +352,7 @@ void test_adc_slope_debug(void)
     for (int i = 0; i < ADC1_TEST_CHANNEL_NUM; i++) {
         adc_fake_tie_middle(ADC_UNIT_1, adc1_ch[i]);
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 
     while (1) {
         /* adc Read */
@@ -360,7 +360,7 @@ void test_adc_slope_debug(void)
             scope_temp[i] = adc1_get_raw((adc1_channel_t)adc1_ch[i]);
         }
         test_tp_print_to_scope(scope_temp, ADC1_TEST_CHANNEL_NUM);
-        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
     }
 #elif SCOPE_DEBUG_TYPE == 1
     int adc2_val[ADC2_TEST_CHANNEL_NUM] = {0};
@@ -375,7 +375,7 @@ void test_adc_slope_debug(void)
     for (int i = 0; i < ADC2_TEST_CHANNEL_NUM; i++) {
         adc_fake_tie_middle(ADC_UNIT_2, adc2_ch[i]);
     }
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
 
     while (1) {
         /* adc Read */
@@ -386,7 +386,7 @@ void test_adc_slope_debug(void)
         }
 
         test_tp_print_to_scope(scope_temp, ADC2_TEST_CHANNEL_NUM);
-        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
     }
 #endif
 }

+ 5 - 5
components/driver/test/test_dac.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -62,7 +62,7 @@ TEST_CASE("DAC output (RTC) check by adc", "[dac]")
     printf("adc2_init...\n");
     TEST_ESP_OK( adc2_config_channel_atten( ADC_TEST_CHANNEL_NUM, ADC_TEST_ATTEN ) );
 
-    vTaskDelay(2 * portTICK_RATE_MS);
+    vTaskDelay(2 * portTICK_PERIOD_MS);
 
     printf("start conversion.\n");
     int output_data = 0;
@@ -70,7 +70,7 @@ TEST_CASE("DAC output (RTC) check by adc", "[dac]")
     for (int i = 0; i < DAC_OUT_TIMES; i++) {
         TEST_ESP_OK( dac_output_voltage( DAC_TEST_CHANNEL_NUM, output_data ) );
         output_data += DAC_OUT_STEP;
-        vTaskDelay(2 * portTICK_RATE_MS);
+        vTaskDelay(2 * portTICK_PERIOD_MS);
         TEST_ESP_OK( adc2_get_raw( ADC_TEST_CHANNEL_NUM, ADC_TEST_WIDTH, &read_raw) );
         ESP_LOGI(TAG, "DAC%d - ADC%d", output_data, read_raw);
         if (read_old != 0) {
@@ -110,12 +110,12 @@ TEST_CASE("DAC cw generator output (RTC) check by adc", "[dac]")
     printf("adc2_init...\n");
     TEST_ESP_OK( adc2_config_channel_atten( ADC_TEST_CHANNEL_NUM, ADC_TEST_ATTEN ) );
 
-    vTaskDelay(2 * portTICK_RATE_MS);
+    vTaskDelay(2 * portTICK_PERIOD_MS);
 
     printf("start conversion.\n");
     int read_raw[3] = {0};
     for (int i = 0; i < DAC_TEST_TIMES; i++) {
-        vTaskDelay(10 * portTICK_RATE_MS);
+        vTaskDelay(10 * portTICK_PERIOD_MS);
         TEST_ESP_OK( adc2_get_raw( ADC_TEST_CHANNEL_NUM, ADC_TEST_WIDTH, &read_raw[0]) );
         ESP_LOGI(TAG, "ADC: %d", read_raw[0]);
         /* Should open after dac cali. */

+ 38 - 38
components/driver/test/test_gpio.c

@@ -161,7 +161,7 @@ static void trigger_wake_up(void *arg)
     gpio_install_isr_service(0);
     gpio_isr_handler_add(TEST_GPIO_EXT_OUT_IO, gpio_isr_level_handler, (void *) TEST_GPIO_EXT_IN_IO);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
 }
 #endif //!WAKE_UP_IGNORE
 
@@ -244,7 +244,7 @@ TEST_CASE("GPIO rising edge interrupt test", "[gpio][test_env=UT_T1_GPIO]")
     gpio_isr_handler_add(TEST_GPIO_EXT_IN_IO, gpio_isr_edge_handler, (void *)TEST_GPIO_EXT_IN_IO);
     TEST_ESP_OK(gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1));
     TEST_ASSERT_EQUAL_INT(edge_intr_times, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
 }
@@ -265,9 +265,9 @@ TEST_CASE("GPIO falling edge interrupt test", "[gpio][test_env=UT_T1_GPIO]")
     gpio_install_isr_service(0);
     gpio_isr_handler_add(TEST_GPIO_EXT_IN_IO, gpio_isr_edge_handler, (void *) TEST_GPIO_EXT_IN_IO);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 0);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT(edge_intr_times, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
 }
@@ -295,9 +295,9 @@ TEST_CASE("GPIO both rising and falling edge interrupt test", "[gpio][test_env=U
         if (level > 10) {
             break;
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     // for falling rdge in GPIO_INTR_ANYEDGE
     while (1) {
         level = level - 1;
@@ -305,11 +305,11 @@ TEST_CASE("GPIO both rising and falling edge interrupt test", "[gpio][test_env=U
         if (level < 0) {
             break;
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT(edge_intr_times, 2);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
 }
@@ -330,7 +330,7 @@ TEST_CASE("GPIO input high level trigger, cut the interrupt source exit interrup
     gpio_install_isr_service(0);
     gpio_isr_handler_add(TEST_GPIO_EXT_IN_IO, gpio_isr_level_handler2, (void *) TEST_GPIO_EXT_IN_IO);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(level_intr_times, 1, "go into high-level interrupt more than once with cur interrupt source way");
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
@@ -354,7 +354,7 @@ TEST_CASE("GPIO low level interrupt test", "[gpio][test_env=UT_T1_GPIO]")
     gpio_isr_handler_add(TEST_GPIO_EXT_IN_IO, gpio_isr_level_handler, (void *) TEST_GPIO_EXT_IN_IO);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 0);
     printf("get level:%d\n", gpio_get_level(TEST_GPIO_EXT_IN_IO));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(disable_intr_times, 1, "go into low-level interrupt more than once with disable way");
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
@@ -376,10 +376,10 @@ TEST_CASE("GPIO multi-level interrupt test, to cut the interrupt source exit int
     gpio_install_isr_service(0);
     gpio_isr_handler_add(TEST_GPIO_EXT_IN_IO, gpio_isr_level_handler2, (void *) TEST_GPIO_EXT_IN_IO);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(level_intr_times, 1, "go into high-level interrupt more than once with cur interrupt source way");
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
-    vTaskDelay(200 / portTICK_RATE_MS);
+    vTaskDelay(200 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(level_intr_times, 2, "go into high-level interrupt more than once with cur interrupt source way");
     gpio_isr_handler_remove(TEST_GPIO_EXT_IN_IO);
     gpio_uninstall_isr_service();
@@ -406,7 +406,7 @@ TEST_CASE("GPIO enable and disable interrupt test", "[gpio][test_env=UT_T1_GPIO]
     TEST_ASSERT_EQUAL_INT_MESSAGE(disable_intr_times, 1, "go into high-level interrupt more than once with disable way");
 
     // not install service now
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_intr_disable(TEST_GPIO_EXT_IN_IO));
     TEST_ESP_OK(gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1));
     TEST_ASSERT_EQUAL_INT_MESSAGE(disable_intr_times, 1, "disable interrupt does not work, still go into interrupt!");
@@ -442,9 +442,9 @@ TEST_CASE("GPIO interrupt on other CPUs test", "[gpio]")
         TEST_ESP_OK(gpio_set_level(TEST_GPIO_EXT_OUT_IO, 0));
         xTaskCreatePinnedToCore(install_isr_service_task, "install_isr_service_task", 2048, (void *) TEST_GPIO_EXT_OUT_IO, 1, &gpio_task_handle, cpu_num);
 
-        vTaskDelay(200 / portTICK_RATE_MS);
+        vTaskDelay(200 / portTICK_PERIOD_MS);
         TEST_ESP_OK(gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1));
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
         TEST_ASSERT_EQUAL_INT(edge_intr_times, 1);
         gpio_isr_handler_remove(TEST_GPIO_EXT_OUT_IO);
         gpio_uninstall_isr_service();
@@ -473,7 +473,7 @@ TEST_CASE("GPIO set gpio output level test", "[gpio][ignore][UT_T1_GPIO]")
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 0);
     // tested voltage is around 0v
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 0, "get level error! the level should be low!");
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
     // tested voltage is around 3.3v
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 1, "get level error! the level should be high!");
@@ -514,16 +514,16 @@ TEST_CASE("GPIO io pull up/down function", "[gpio]")
     gpio_config(&io_conf);
     gpio_set_direction(TEST_GPIO_EXT_IN_IO, GPIO_MODE_INPUT);
     TEST_ESP_OK(gpio_pullup_en(TEST_GPIO_EXT_IN_IO));  // pull up first
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 1, "gpio_pullup_en error, it can't pull up");
     TEST_ESP_OK(gpio_pulldown_dis(TEST_GPIO_EXT_IN_IO)); //can't be pull down
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 1, "gpio_pulldown_dis error, it can pull down");
     TEST_ESP_OK(gpio_pulldown_en(TEST_GPIO_EXT_IN_IO)); // can be pull down now
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 0, "gpio_pulldown_en error, it can't pull down");
     TEST_ESP_OK(gpio_pullup_dis(TEST_GPIO_EXT_IN_IO)); // can't be pull up
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(TEST_GPIO_EXT_IN_IO), 0, "gpio_pullup_dis error, it can pull up");
 }
 
@@ -609,13 +609,13 @@ TEST_CASE("GPIO wake up enable and disenable test", "[gpio][ignore]")
 {
     xTaskCreate(sleep_wake_up, "sleep_wake_up", 4096, NULL, 5, NULL);
     xTaskCreate(trigger_wake_up, "trigger_wake_up", 4096, NULL, 5, NULL);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_TRUE(wake_up_result);
 
     wake_up_result = false;
     TEST_ESP_OK(gpio_wakeup_disable(TEST_GPIO_EXT_IN_IO));
     gpio_set_level(TEST_GPIO_EXT_OUT_IO, 1);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_FALSE(wake_up_result);
 }
 #endif // !WAKE_UP_IGNORE
@@ -757,19 +757,19 @@ TEST_CASE("GPIO Enable/Disable interrupt on multiple cores", "[gpio][ignore]")
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 0));
     TEST_ESP_OK(gpio_install_isr_service(0));
     TEST_ESP_OK(gpio_isr_handler_add(TEST_IO_9, gpio_isr_edge_handler, (void *) TEST_IO_9));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 1));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 0));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_intr_disable(TEST_IO_9));
     TEST_ASSERT(edge_intr_times == 1);
     xTaskCreatePinnedToCore(gpio_enable_task, "gpio_enable_task", 1024 * 4, (void *)TEST_IO_9, 8, NULL, (xPortGetCoreID() == 0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 1));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 0));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_intr_disable(TEST_IO_9));
     TEST_ESP_OK(gpio_isr_handler_remove(TEST_IO_9));
     gpio_uninstall_isr_service();
@@ -824,24 +824,24 @@ TEST_CASE("GPIO ISR service test", "[gpio][ignore]")
     TEST_ESP_OK(gpio_isr_handler_add(TEST_IO_9, gpio_isr_handler, (void *)&io9_param));
     TEST_ESP_OK(gpio_isr_handler_add(TEST_IO_10, gpio_isr_handler, (void *)&io10_param));
     printf("Triggering the interrupt of GPIO9\n");
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     //Rising edge
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 1));
     printf("Disable the interrupt of GPIO9\n");
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     //Disable GPIO9 interrupt, GPIO18 will not respond to the next falling edge interrupt.
     TEST_ESP_OK(gpio_intr_disable(TEST_IO_9));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     //Falling edge
     TEST_ESP_OK(gpio_set_level(TEST_IO_9, 0));
 
     printf("Triggering the interrupt of GPIO10\n");
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_set_level(TEST_IO_10, 1));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     //Falling edge
     TEST_ESP_OK(gpio_set_level(TEST_IO_10, 0));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(gpio_isr_handler_remove(TEST_IO_9));
     TEST_ESP_OK(gpio_isr_handler_remove(TEST_IO_10));
     gpio_uninstall_isr_service();
@@ -868,17 +868,17 @@ TEST_CASE("GPIO input and output of USB pins test", "[gpio]")
         // tested voltage is around 0v
         esp_rom_delay_us(10);
         TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(pin), 0, "get level error! the level should be low!");
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         gpio_set_level(pin, 1);
         esp_rom_delay_us(10);
         // tested voltage is around 3.3v
         TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(pin), 1, "get level error! the level should be high!");
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         gpio_set_level(pin, 0);
         esp_rom_delay_us(10);
         // tested voltage is around 0v
         TEST_ASSERT_EQUAL_INT_MESSAGE(gpio_get_level(pin), 0, "get level error! the level should be low!");
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         gpio_set_level(pin, 1);
         esp_rom_delay_us(10);
         // tested voltage is around 3.3v

+ 17 - 17
components/driver/test/test_i2c.c

@@ -87,7 +87,7 @@ static esp_err_t i2c_master_write_slave(i2c_port_t i2c_num, uint8_t *data_wr, si
     TEST_ESP_OK(i2c_master_write_byte(cmd, ( ESP_SLAVE_ADDR << 1 ) | WRITE_BIT, ACK_CHECK_EN));
     TEST_ESP_OK(i2c_master_write(cmd, data_wr, size, ACK_CHECK_EN));
     TEST_ESP_OK(i2c_master_stop(cmd));
-    esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, 5000 / portTICK_RATE_MS);
+    esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, 5000 / portTICK_PERIOD_MS);
     i2c_cmd_link_delete(cmd);
     return ret;
 }
@@ -268,7 +268,7 @@ TEST_CASE("I2C driver memory leaking check", "[i2c]")
                                  I2C_SLAVE_RX_BUF_LEN,
                                  I2C_SLAVE_TX_BUF_LEN, 0);
         TEST_ASSERT(ret == ESP_OK);
-        vTaskDelay(10 / portTICK_RATE_MS);
+        vTaskDelay(10 / portTICK_PERIOD_MS);
         i2c_driver_delete(I2C_SLAVE_NUM);
         TEST_ASSERT(ret == ESP_OK);
     }
@@ -330,7 +330,7 @@ static void i2c_slave_read_test(void)
 
     unity_wait_for_signal("master write");
     while (1) {
-        len = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd + size_rd, DATA_LENGTH, 10000 / portTICK_RATE_MS);
+        len = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd + size_rd, DATA_LENGTH, 10000 / portTICK_PERIOD_MS);
         if (len == 0) {
             break;
         }
@@ -367,9 +367,9 @@ static void master_read_slave_test(void)
     i2c_master_read(cmd, data_rd, RW_TEST_LENGTH-1, ACK_VAL);
     i2c_master_read_byte(cmd, data_rd + RW_TEST_LENGTH-1, NACK_VAL);
     i2c_master_stop(cmd);
-    i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 5000 / portTICK_RATE_MS);
+    i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 5000 / portTICK_PERIOD_MS);
     i2c_cmd_link_delete(cmd);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     for (int i = 0; i < RW_TEST_LENGTH; i++) {
         printf("%d\n", data_rd[i]);
         TEST_ASSERT(data_rd[i]==i);
@@ -395,7 +395,7 @@ static void slave_write_buffer_test(void)
     for (int i = 0; i < DATA_LENGTH / 2; i++) {
         data_wr[i] = i;
     }
-    size_rd = i2c_slave_write_buffer(I2C_SLAVE_NUM, data_wr, RW_TEST_LENGTH, 2000 / portTICK_RATE_MS);
+    size_rd = i2c_slave_write_buffer(I2C_SLAVE_NUM, data_wr, RW_TEST_LENGTH, 2000 / portTICK_PERIOD_MS);
     disp_buf(data_wr, size_rd);
     unity_send_signal("master read");
     unity_wait_for_signal("ready to delete");
@@ -428,9 +428,9 @@ static void i2c_master_write_read_test(void)
     i2c_master_read(cmd, data_rd, RW_TEST_LENGTH, ACK_VAL);
     i2c_master_read_byte(cmd, data_rd + RW_TEST_LENGTH, NACK_VAL);
     i2c_master_stop(cmd);
-    i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 5000 / portTICK_RATE_MS);
+    i2c_master_cmd_begin(I2C_MASTER_NUM, cmd, 5000 / portTICK_PERIOD_MS);
     i2c_cmd_link_delete(cmd);
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     disp_buf(data_rd, RW_TEST_LENGTH);
     for (int i = 0; i < RW_TEST_LENGTH; i++) {
         TEST_ASSERT(data_rd[i] == i/2);
@@ -440,7 +440,7 @@ static void i2c_master_write_read_test(void)
         data_wr[i] = i % 3;
     }
 
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     i2c_master_write_slave(I2C_MASTER_NUM, data_wr, RW_TEST_LENGTH);
     free(data_wr);
     free(data_rd);
@@ -467,11 +467,11 @@ static void i2c_slave_read_write_test(void)
     for (int i = 0; i < DATA_LENGTH / 2; i++) {
         data_wr[i] = i/2;
     }
-    size_rd = i2c_slave_write_buffer(I2C_SLAVE_NUM, data_wr, RW_TEST_LENGTH, 2000 / portTICK_RATE_MS);
+    size_rd = i2c_slave_write_buffer(I2C_SLAVE_NUM, data_wr, RW_TEST_LENGTH, 2000 / portTICK_PERIOD_MS);
     disp_buf(data_wr, size_rd);
     unity_send_signal("master read and write");
     unity_wait_for_signal("slave read");
-    size_rd = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd, RW_TEST_LENGTH, 1000 / portTICK_RATE_MS);
+    size_rd = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd, RW_TEST_LENGTH, 1000 / portTICK_PERIOD_MS);
     printf("slave read data is:\n");
     disp_buf(data_rd, size_rd);
     for (int i = 0; i < RW_TEST_LENGTH; i++) {
@@ -526,7 +526,7 @@ static void i2c_slave_repeat_read(void)
     unity_wait_for_signal("master write");
 
     while (1) {
-        int len = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd + size_rd, RW_TEST_LENGTH * 3, 10000 / portTICK_RATE_MS);
+        int len = i2c_slave_read_buffer( I2C_SLAVE_NUM, data_rd + size_rd, RW_TEST_LENGTH * 3, 10000 / portTICK_PERIOD_MS);
         if (len == 0) {
             break;
         }
@@ -555,7 +555,7 @@ static bool test_read_func;
 
 static void test_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
 
     uint8_t *data = (uint8_t *) malloc(DATA_LENGTH);
     i2c_config_t conf_slave = i2c_slave_init();
@@ -569,7 +569,7 @@ static void test_task(void *pvParameters)
         } else {
             i2c_slave_write_buffer(I2C_SLAVE_NUM, data, DATA_LENGTH, 0);
         }
-        vTaskDelay(10/portTICK_RATE_MS);
+        vTaskDelay(10/portTICK_PERIOD_MS);
     }
 
     free(data);
@@ -579,7 +579,7 @@ static void test_task(void *pvParameters)
 
 TEST_CASE("test i2c_slave_read_buffer is not blocked when ticks_to_wait=0", "[i2c]")
 {
-    xSemaphoreHandle exit_sema = xSemaphoreCreateBinary();
+    SemaphoreHandle_t exit_sema = xSemaphoreCreateBinary();
     exit_flag = false;
 
     test_read_func = true;
@@ -598,7 +598,7 @@ TEST_CASE("test i2c_slave_read_buffer is not blocked when ticks_to_wait=0", "[i2
 
 TEST_CASE("test i2c_slave_write_buffer is not blocked when ticks_to_wait=0", "[i2c]")
 {
-    xSemaphoreHandle exit_sema = xSemaphoreCreateBinary();
+    SemaphoreHandle_t exit_sema = xSemaphoreCreateBinary();
     exit_flag = false;
 
     test_read_func = false;
@@ -715,7 +715,7 @@ TEST_CASE("I2C SCL freq test (local test)", "[i2c][ignore]")
     i2c_master_start(cmd);
     i2c_master_write(cmd, data, 30, ACK_CHECK_DIS);
     i2c_master_stop(cmd);
-    i2c_master_cmd_begin(i2c_num, cmd, 5000 / portTICK_RATE_MS);
+    i2c_master_cmd_begin(i2c_num, cmd, 5000 / portTICK_PERIOD_MS);
     i2c_cmd_link_delete(cmd);
     i2c_scl_freq_cal();
     free(data);

+ 2 - 2
components/driver/test/test_i2s.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -673,7 +673,7 @@ TEST_CASE("I2S adc test", "[i2s]")
             } else {
                 gpio_set_pull_mode(ADC1_CHANNEL_4_IO, GPIO_PULLUP_ONLY);
             }
-            vTaskDelay(200 / portTICK_RATE_MS);
+            vTaskDelay(200 / portTICK_PERIOD_MS);
             // read data from adc, will block until buffer is full
             i2s_read(I2S_NUM_0, (void *)i2sReadBuffer, 1024 * sizeof(uint16_t), &bytesRead, portMAX_DELAY);
 

+ 17 - 17
components/driver/test/test_ledc.c

@@ -78,7 +78,7 @@ static void fade_setup(void)
 
     TEST_ESP_OK(ledc_channel_config(&ledc_ch_config));
     TEST_ESP_OK(ledc_timer_config(&ledc_time_config));
-    vTaskDelay(5 / portTICK_RATE_MS);
+    vTaskDelay(5 / portTICK_PERIOD_MS);
 
     //initialize fade service
     TEST_ESP_OK(ledc_fade_func_install(0));
@@ -88,7 +88,7 @@ static void timer_duty_set_get(ledc_mode_t speed_mode, ledc_channel_t channel, u
 {
     TEST_ESP_OK(ledc_set_duty(speed_mode, channel, duty));
     TEST_ESP_OK(ledc_update_duty(speed_mode, channel));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(duty, ledc_get_duty(speed_mode, channel));
 }
 
@@ -143,11 +143,11 @@ static int16_t wave_count(int last_time)
     // initialize first
     TEST_ESP_OK(pcnt_counter_pause(PCNT_UNIT_0));
     TEST_ESP_OK(pcnt_counter_clear(PCNT_UNIT_0));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
 
-    vTaskDelay(last_time / portTICK_RATE_MS);
+    vTaskDelay(last_time / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     return test_counter;
 }
@@ -269,7 +269,7 @@ TEST_CASE("LEDC error log channel and timer config", "[ledc]")
 
     uint32_t current_level = LEDC.channel_group[test_speed_mode].channel[LEDC_CHANNEL_0].conf0.idle_lv;
     TEST_ESP_OK(ledc_stop(test_speed_mode, LEDC_CHANNEL_0, !current_level));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(LEDC.channel_group[test_speed_mode].channel[LEDC_CHANNEL_0].conf0.idle_lv, !current_level);
 }
 
@@ -344,7 +344,7 @@ TEST_CASE("LEDC fade with time", "[ledc]")
     TEST_ESP_OK(ledc_fade_start(test_speed_mode, LEDC_CHANNEL_0, LEDC_FADE_NO_WAIT));
     // duty should not be too far from initial value
     TEST_ASSERT_INT32_WITHIN(20, 4000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
-    vTaskDelay(210 / portTICK_RATE_MS);
+    vTaskDelay(210 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(0, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
 
     //deinitialize fade service
@@ -364,7 +364,7 @@ TEST_CASE("LEDC fade with step", "[ledc]")
     TEST_ESP_OK(ledc_fade_start(test_speed_mode, LEDC_CHANNEL_0, LEDC_FADE_NO_WAIT));
     // duty should not be too far from initial value
     TEST_ASSERT_INT32_WITHIN(20, 4000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
-    vTaskDelay(525 / portTICK_RATE_MS);
+    vTaskDelay(525 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(0, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
 
     //scaler=0 check
@@ -398,7 +398,7 @@ TEST_CASE("LEDC fast switching duty with fade_wait_done", "[ledc]")
     TEST_ASSERT_EQUAL_INT32(4000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
     TEST_ESP_OK(ledc_set_duty(test_speed_mode, LEDC_CHANNEL_0, 500));
     TEST_ESP_OK(ledc_update_duty(test_speed_mode, LEDC_CHANNEL_0));
-    vTaskDelay(5 / portTICK_RATE_MS);
+    vTaskDelay(5 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(500, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
 
     //deinitialize fade service
@@ -423,7 +423,7 @@ TEST_CASE("LEDC fast switching duty with fade_no_wait", "[ledc]")
     TEST_ASSERT_INT32_WITHIN(20, 4000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
     int time_ms = (first_fade_complete - fade_start) / 1000;
     TEST_ASSERT_TRUE(fabs(time_ms - 200) < 20);
-    vTaskDelay(158 / portTICK_RATE_MS);
+    vTaskDelay(158 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(1000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
 
     // next duty update will not take place until last fade reaches its target duty
@@ -432,7 +432,7 @@ TEST_CASE("LEDC fast switching duty with fade_no_wait", "[ledc]")
     TEST_ASSERT_LESS_THAN(4000, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
     TEST_ESP_OK(ledc_set_duty(test_speed_mode, LEDC_CHANNEL_0, 500));
     TEST_ESP_OK(ledc_update_duty(test_speed_mode, LEDC_CHANNEL_0));
-    vTaskDelay(5 / portTICK_RATE_MS);
+    vTaskDelay(5 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(500, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
 
     //deinitialize fade service
@@ -451,7 +451,7 @@ TEST_CASE("LEDC fade stop test", "[ledc]")
     TEST_ESP_OK(ledc_set_fade_with_time(test_speed_mode, LEDC_CHANNEL_0, 4000, 500));
     TEST_ESP_OK(ledc_fade_start(test_speed_mode, LEDC_CHANNEL_0, LEDC_FADE_NO_WAIT));
     // Add some delay before stopping the fade
-    vTaskDelay(127 / portTICK_RATE_MS);
+    vTaskDelay(127 / portTICK_PERIOD_MS);
     // Get duty value right before stopping the fade
     uint32_t duty_before_stop = ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0);
     TEST_ESP_OK(ledc_fade_stop(test_speed_mode, LEDC_CHANNEL_0));
@@ -461,7 +461,7 @@ TEST_CASE("LEDC fade stop test", "[ledc]")
     // Get duty value after fade_stop returns (give at least one cycle for the duty set in fade_stop to take effective)
     uint32_t duty_after_stop = ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0);
     TEST_ASSERT_INT32_WITHIN(4, duty_before_stop, duty_after_stop); // 4 is the scale for one step in the last fade
-    vTaskDelay(300 / portTICK_RATE_MS);
+    vTaskDelay(300 / portTICK_PERIOD_MS);
     // Duty should not change any more after ledc_fade_stop returns
     TEST_ASSERT_EQUAL_INT32(duty_after_stop, ledc_get_duty(test_speed_mode, LEDC_CHANNEL_0));
     TEST_ASSERT_NOT_EQUAL(4000, duty_after_stop);
@@ -532,12 +532,12 @@ TEST_CASE("LEDC timer set", "[ledc][test_env=UT_T1_LEDC]")
 
     printf("Bind channel 0 to timer 0\n");
     TEST_ESP_OK(ledc_bind_channel_timer(test_speed_mode, LEDC_CHANNEL_0, LEDC_TIMER_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32(ledc_get_freq(test_speed_mode, LEDC_TIMER_0), 500);
 
     uint32_t current_level = LEDC.channel_group[test_speed_mode].channel[LEDC_CHANNEL_0].conf0.idle_lv;
     TEST_ESP_OK(ledc_stop(test_speed_mode, LEDC_CHANNEL_0, !current_level));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL_INT32( LEDC.channel_group[test_speed_mode].channel[LEDC_CHANNEL_0].conf0.idle_lv, !current_level);
 }
 
@@ -571,7 +571,7 @@ TEST_CASE("LEDC timer pause and resume", "[ledc][test_env=UT_T1_LEDC]")
     //pause ledc timer, when pause it, will get no waveform count
     printf("Pause ledc timer\n");
     TEST_ESP_OK(ledc_timer_pause(test_speed_mode, LEDC_TIMER_0));
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
     count = wave_count(1000);
     TEST_ASSERT_INT16_WITHIN(5, count, 0);
     TEST_ASSERT_EQUAL_UINT32(count, 0);
@@ -579,14 +579,14 @@ TEST_CASE("LEDC timer pause and resume", "[ledc][test_env=UT_T1_LEDC]")
     //resume ledc timer
     printf("Resume ledc timer\n");
     TEST_ESP_OK(ledc_timer_resume(test_speed_mode, LEDC_TIMER_0));
-    vTaskDelay(10 / portTICK_RATE_MS);
+    vTaskDelay(10 / portTICK_PERIOD_MS);
     count = wave_count(1000);
     TEST_ASSERT_UINT32_WITHIN(5, count, 5000);
 
     //reset ledc timer
     printf("reset ledc timer\n");
     TEST_ESP_OK(ledc_timer_rst(test_speed_mode, LEDC_TIMER_0));
-    vTaskDelay(100 / portTICK_RATE_MS);
+    vTaskDelay(100 / portTICK_PERIOD_MS);
     TEST_ASSERT_UINT32_WITHIN(5, count, 5000);
 }
 

+ 14 - 14
components/driver/test/test_pcnt.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -42,7 +42,7 @@
 #define PCNT_CTRL_HIGH_LEVEL 1
 #define PCNT_CTRL_LOW_LEVEL 0
 
-static xQueueHandle pcnt_evt_queue = NULL;
+static QueueHandle_t pcnt_evt_queue = NULL;
 
 typedef struct {
     int zero_times;
@@ -217,7 +217,7 @@ static void count_mode_test(gpio_num_t ctl_io)
         result = result2;
     }
     // Wait for ledc and pcnt settling down
-    vTaskDelay(500 / portTICK_RATE_MS);
+    vTaskDelay(500 / portTICK_PERIOD_MS);
 
     // 1, 0, 0, 0
     TEST_ESP_OK(pcnt_counter_pause(PCNT_UNIT_0));
@@ -226,7 +226,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_INC, PCNT_COUNT_DIS,
                               PCNT_MODE_KEEP, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[0]);
@@ -238,7 +238,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_DEC, PCNT_COUNT_DIS,
                               PCNT_MODE_KEEP, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[1]);
@@ -250,7 +250,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_DIS, PCNT_COUNT_DIS,
                               PCNT_MODE_KEEP, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[2]);
@@ -262,7 +262,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_INC, PCNT_COUNT_DIS,
                               PCNT_MODE_REVERSE, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[3]);
@@ -274,7 +274,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_INC, PCNT_COUNT_DIS,
                               PCNT_MODE_KEEP, PCNT_MODE_REVERSE));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[4]);
@@ -286,7 +286,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_DEC, PCNT_COUNT_DIS,
                               PCNT_MODE_REVERSE, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[5]);
@@ -298,7 +298,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_INC, PCNT_COUNT_DIS,
                               PCNT_MODE_DISABLE, PCNT_MODE_KEEP));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[6]);
@@ -310,7 +310,7 @@ static void count_mode_test(gpio_num_t ctl_io)
                               PCNT_COUNT_INC, PCNT_COUNT_DIS,
                               PCNT_MODE_KEEP, PCNT_MODE_DISABLE));
     TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
     printf("value: %d\n", test_counter);
     TEST_ASSERT_INT16_WITHIN(1, test_counter, result[7]);
@@ -420,7 +420,7 @@ TEST_CASE("PCNT basic function test", "[pcnt]")
 
     //count now
     while (time != 10) {
-        vTaskDelay(501 / portTICK_RATE_MS);  // in case of can't wait to get counter(edge effect)
+        vTaskDelay(501 / portTICK_PERIOD_MS);  // in case of can't wait to get counter(edge effect)
         TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
         printf("COUNT: %d\n", test_counter);
         TEST_ASSERT_NOT_EQUAL(test_counter, temp_value);
@@ -436,14 +436,14 @@ TEST_CASE("PCNT basic function test", "[pcnt]")
         if (test_counter == 0) {
             //test pause
             TEST_ESP_OK(pcnt_counter_pause(PCNT_UNIT_0));
-            vTaskDelay(500 / portTICK_RATE_MS);
+            vTaskDelay(500 / portTICK_PERIOD_MS);
             TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
             printf("PAUSE: %d\n", test_counter);
             TEST_ASSERT_EQUAL_INT16(test_counter, 0);
 
             // test resume
             TEST_ESP_OK(pcnt_counter_resume(PCNT_UNIT_0));
-            vTaskDelay(500 / portTICK_RATE_MS);
+            vTaskDelay(500 / portTICK_PERIOD_MS);
             TEST_ESP_OK(pcnt_get_counter_value(PCNT_UNIT_0, &test_counter));
             printf("RESUME: %d\n", test_counter);
             TEST_ASSERT_EQUAL_INT16(test_counter, 1);

+ 2 - 2
components/driver/test/test_rs485.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -32,7 +32,7 @@
 #define PACKETS_NUMBER  (10)
 
 // Wait timeout for uart driver
-#define PACKET_READ_TICS    (1000 / portTICK_RATE_MS)
+#define PACKET_READ_TICS    (1000 / portTICK_PERIOD_MS)
 
 #if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S2, ESP32S3, ESP32C3)
 //No runners

+ 10 - 10
components/driver/test/test_rtcio.c

@@ -102,13 +102,13 @@ TEST_CASE("RTCIO input/output test", "[rtcio]")
         for (int i = 0; i < GPIO_PIN_COUNT; i++) {
             if (GPIO_IS_VALID_OUTPUT_GPIO(i) && rtc_gpio_is_valid_gpio(i)) {
                 RTCIO_CHECK( rtc_gpio_set_level(i, level) );
-                vTaskDelay(10 / portTICK_RATE_MS);
+                vTaskDelay(10 / portTICK_PERIOD_MS);
                 if (rtc_gpio_get_level(i) != level) {
                     ESP_LOGE(TAG, "RTCIO input/output test err, gpio%d", i);
                 }
             }
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
 
     // Deinit rtcio
@@ -152,13 +152,13 @@ TEST_CASE("RTCIO pullup/pulldown test", "[rtcio]")
                     RTCIO_CHECK( rtc_gpio_pullup_dis(s_test_map[i]) );
                     RTCIO_CHECK( rtc_gpio_pulldown_en(s_test_map[i]) );
                 }
-                vTaskDelay(20 / portTICK_RATE_MS);
+                vTaskDelay(20 / portTICK_PERIOD_MS);
                 if (rtc_gpio_get_level(s_test_map[i]) != level) {
                     ESP_LOGE(TAG, "RTCIO pullup/pulldown test err, gpio%d", s_test_map[i]);
                 }
             }
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
 
     // Deinit rtcio
@@ -194,13 +194,13 @@ TEST_CASE("RTCIO output OD test", "[rtcio]")
         for (int i = 0; i < GPIO_PIN_COUNT; i++) {
             if (GPIO_IS_VALID_OUTPUT_GPIO(i) && rtc_gpio_is_valid_gpio(i)) {
                 RTCIO_CHECK( rtc_gpio_set_level(i, level) );
-                vTaskDelay(10 / portTICK_RATE_MS);
+                vTaskDelay(10 / portTICK_PERIOD_MS);
                 if (rtc_gpio_get_level(i) != level) {
                     ESP_LOGE(TAG, "RTCIO output OD test err, gpio%d", i);
                 }
             }
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
 
     // Deinit rtcio
@@ -234,10 +234,10 @@ TEST_CASE("RTCIO output hold test", "[rtcio]")
     for (int i = 0; i < GPIO_PIN_COUNT; i++) {
         if (GPIO_IS_VALID_OUTPUT_GPIO(i) && rtc_gpio_is_valid_gpio(i)) {
             RTCIO_CHECK( rtc_gpio_hold_en(i) );
-            vTaskDelay(10 / portTICK_RATE_MS);
+            vTaskDelay(10 / portTICK_PERIOD_MS);
             RTCIO_CHECK( rtc_gpio_set_level(i, 0) );
             ESP_LOGI(TAG, "RTCIO output pin hold, then set level 0");
-            vTaskDelay(10 / portTICK_RATE_MS);
+            vTaskDelay(10 / portTICK_PERIOD_MS);
             if (rtc_gpio_get_level(i) == 0) {
                 ESP_LOGE(TAG, "RTCIO hold test err, gpio%d", i);
             }
@@ -258,13 +258,13 @@ TEST_CASE("RTCIO output hold test", "[rtcio]")
         for (int i = 0; i < GPIO_PIN_COUNT; i++) {
             if (GPIO_IS_VALID_OUTPUT_GPIO(i) && rtc_gpio_is_valid_gpio(i)) {
                 RTCIO_CHECK( rtc_gpio_set_level(i, level) );
-                vTaskDelay(10 / portTICK_RATE_MS);
+                vTaskDelay(10 / portTICK_PERIOD_MS);
                 if (rtc_gpio_get_level(i) != level) {
                     ESP_LOGE(TAG, "RTCIO output OD test err, gpio%d", i);
                 }
             }
         }
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
 
     // Deinit rtcio

+ 8 - 8
components/driver/test/test_uart.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -30,7 +30,7 @@
 #define PACKETS_NUMBER  (10)
 
 // Wait timeout for uart driver
-#define PACKET_READ_TICS    (1000 / portTICK_RATE_MS)
+#define PACKET_READ_TICS    (1000 / portTICK_PERIOD_MS)
 
 #define TEST_DEFAULT_CLK UART_SCLK_APB
 
@@ -54,7 +54,7 @@ static volatile bool exit_flag;
 
 static void test_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     char* data = (char *) malloc(256);
 
     while (exit_flag == false) {
@@ -82,7 +82,7 @@ TEST_CASE("test uart_wait_tx_done is not blocked when ticks_to_wait=0", "[uart]"
 {
     uart_config(UART_BAUD_11520, TEST_DEFAULT_CLK);
 
-    xSemaphoreHandle exit_sema = xSemaphoreCreateBinary();
+    SemaphoreHandle_t exit_sema = xSemaphoreCreateBinary();
     exit_flag = false;
 
     xTaskCreate(test_task,  "tsk1", 2048, &exit_sema, 5, NULL);
@@ -132,7 +132,7 @@ TEST_CASE("test uart tx data with break", "[uart]")
     uart_config(UART_BAUD_115200, TEST_DEFAULT_CLK);
     printf("Uart%d send %d bytes with break\n", UART_NUM1, send_len);
     uart_write_bytes_with_break(UART_NUM1, (const char *)psend, send_len, brk_len);
-    uart_wait_tx_done(UART_NUM1, (portTickType)portMAX_DELAY);
+    uart_wait_tx_done(UART_NUM1, (TickType_t)portMAX_DELAY);
     //If the code is running here, it means the test passed, otherwise it will crash due to the interrupt wdt timeout.
     printf("Send data with break test passed\n");
     free(psend);
@@ -396,7 +396,7 @@ TEST_CASE("uart int state restored after flush", "[uart]")
     uart_write_bytes(uart_echo, (const char *) data, buf_size);
 
     /* As we set up a loopback, we can read them back on RX */
-    int len = uart_read_bytes(uart_echo, data, buf_size, 1000 / portTICK_RATE_MS);
+    int len = uart_read_bytes(uart_echo, data, buf_size, 1000 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL(len, buf_size);
 
     /* Fill the RX buffer, this should disable the RX interrupts */
@@ -411,7 +411,7 @@ TEST_CASE("uart int state restored after flush", "[uart]")
     uart_flush_input(uart_echo);
     written = uart_write_bytes(uart_echo, (const char *) data, buf_size);
     TEST_ASSERT_NOT_EQUAL(-1, written);
-    len = uart_read_bytes(uart_echo, data, buf_size, 1000 / portTICK_RATE_MS);
+    len = uart_read_bytes(uart_echo, data, buf_size, 1000 / portTICK_PERIOD_MS);
     /* len equals buf_size bytes if interrupts were indeed re-enabled */
     TEST_ASSERT_EQUAL(len, buf_size);
 
@@ -426,7 +426,7 @@ TEST_CASE("uart int state restored after flush", "[uart]")
     uart_flush_input(uart_echo);
     written = uart_write_bytes(uart_echo, (const char *) data, buf_size);
     TEST_ASSERT_NOT_EQUAL(-1, written);
-    len = uart_read_bytes(uart_echo, data, buf_size, 250 / portTICK_RATE_MS);
+    len = uart_read_bytes(uart_echo, data, buf_size, 250 / portTICK_PERIOD_MS);
     TEST_ASSERT_EQUAL(len, 0);
 
     TEST_ESP_OK(uart_driver_delete(uart_echo));

+ 4 - 4
components/driver/test/touch_sensor_test/test_touch_v2.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -2070,7 +2070,7 @@ void test_touch_slope_debug(int pad_num)
             scope_temp[i] = scope_data[i];
         }
         test_tp_print_to_scope(scope_temp, TEST_TOUCH_CHANNEL);
-        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
     }
 #elif SCOPE_DEBUG_TYPE == 1
     while (1) {
@@ -2084,13 +2084,13 @@ void test_touch_slope_debug(int pad_num)
             scope_temp[i + SCOPE_DEBUG_CHANNEL_MAX / 2] = scope_data[i];
         }
         test_tp_print_to_scope(scope_temp, SCOPE_DEBUG_CHANNEL_MAX);
-        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        vTaskDelay(SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
     }
 #elif SCOPE_DEBUG_TYPE == 2
     uint32_t status;
     touch_pad_read_benchmark(pad_num, &status);
     while (1) {
-        xQueueReceive(que_touch, &evt, SCOPE_DEBUG_FREQ_MS / portTICK_RATE_MS);
+        xQueueReceive(que_touch, &evt, SCOPE_DEBUG_FREQ_MS / portTICK_PERIOD_MS);
         //read filtered value
         touch_pad_read_raw_data(pad_num, &scope_data[0]);
         touch_pad_read_benchmark(pad_num, &scope_data[1]);

+ 12 - 12
components/driver/test_apps/gptimer/main/test_gptimer.c

@@ -126,7 +126,7 @@ TEST_CASE("gptimer_wallclock_with_various_clock_sources", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_stop_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     gptimer_stop(timer);
     esp_rom_printf("count=%lld @alarm\n", edata->count_value);
@@ -136,7 +136,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_stop_callback(gptimer_ha
 
 TEST_CASE("gptimer_stop_on_alarm", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,
@@ -199,7 +199,7 @@ TEST_CASE("gptimer_stop_on_alarm", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_reload_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
     // check if the count value has been reloaded
@@ -210,7 +210,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_reload_callback(gptimer_
 
 TEST_CASE("gptimer_auto_reload_on_alarm", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,
@@ -251,7 +251,7 @@ TEST_CASE("gptimer_auto_reload_on_alarm", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_normal_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
     // check the count value at alarm event
@@ -261,7 +261,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_normal_callback(gptimer_
 
 TEST_CASE("gptimer_one_shot_alarm", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,
@@ -311,7 +311,7 @@ TEST_CASE("gptimer_one_shot_alarm", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_update_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
     gptimer_alarm_config_t alarm_config = {
@@ -324,7 +324,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_alarm_update_callback(gptimer_
 
 TEST_CASE("gptimer_update_alarm_dynamically", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,
@@ -375,7 +375,7 @@ TEST_CASE("gptimer_update_alarm_dynamically", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_count_down_reload_alarm_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
     // check if the count value has been reloaded
@@ -386,7 +386,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_count_down_reload_alarm_callba
 
 TEST_CASE("gptimer_count_down_reload", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,
@@ -434,7 +434,7 @@ TEST_CASE("gptimer_count_down_reload", "[gptimer]")
 
 TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_overflow_reload_callback(gptimer_handle_t timer, const gptimer_alarm_event_data_t *edata, void *user_data)
 {
-    xTaskHandle task_handle = (xTaskHandle)user_data;
+    TaskHandle_t task_handle = (TaskHandle_t)user_data;
     BaseType_t high_task_wakeup;
     // Note: esp_rom_printf can't print value with 64 bit length, so the following print result is meaningless, but as an incidator for test that the alarm has fired
     esp_rom_printf("alarm isr count=%llu\r\n", edata->count_value);
@@ -444,7 +444,7 @@ TEST_ALARM_CALLBACK_ATTR static bool test_gptimer_overflow_reload_callback(gptim
 
 TEST_CASE("gptimer_overflow", "[gptimer]")
 {
-    xTaskHandle task_handle =  xTaskGetCurrentTaskHandle();
+    TaskHandle_t task_handle =  xTaskGetCurrentTaskHandle();
 
     gptimer_config_t timer_config = {
         .resolution_hz = 1 * 1000 * 1000,

+ 11 - 11
components/driver/uart.c

@@ -1098,9 +1098,9 @@ esp_err_t uart_wait_tx_done(uart_port_t uart_num, TickType_t ticks_to_wait)
     ESP_RETURN_ON_FALSE((uart_num < UART_NUM_MAX), ESP_FAIL, UART_TAG, "uart_num error");
     ESP_RETURN_ON_FALSE((p_uart_obj[uart_num]), ESP_FAIL, UART_TAG, "uart driver error");
     BaseType_t res;
-    portTickType ticks_start = xTaskGetTickCount();
+    TickType_t ticks_start = xTaskGetTickCount();
     //Take tx_mux
-    res = xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (portTickType)ticks_to_wait);
+    res = xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (TickType_t)ticks_to_wait);
     if (res == pdFALSE) {
         return ESP_ERR_TIMEOUT;
     }
@@ -1120,7 +1120,7 @@ esp_err_t uart_wait_tx_done(uart_port_t uart_num, TickType_t ticks_to_wait)
         ticks_to_wait = ticks_to_wait - (ticks_end - ticks_start);
     }
     //take 2nd tx_done_sem, wait given from ISR
-    res = xSemaphoreTake(p_uart_obj[uart_num]->tx_done_sem, (portTickType)ticks_to_wait);
+    res = xSemaphoreTake(p_uart_obj[uart_num]->tx_done_sem, (TickType_t)ticks_to_wait);
     if (res == pdFALSE) {
         // The TX_DONE interrupt will be disabled in ISR
         xSemaphoreGive(p_uart_obj[uart_num]->tx_mux);
@@ -1139,7 +1139,7 @@ int uart_tx_chars(uart_port_t uart_num, const char *buffer, uint32_t len)
         return 0;
     }
     int tx_len = 0;
-    xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (TickType_t)portMAX_DELAY);
     if (UART_IS_MODE_SET(uart_num, UART_MODE_RS485_HALF_DUPLEX)) {
         UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
         uart_hal_set_rts(&(uart_context[uart_num].hal), 0);
@@ -1159,7 +1159,7 @@ static int uart_tx_all(uart_port_t uart_num, const char *src, size_t size, bool
     size_t original_size = size;
 
     //lock for uart_tx
-    xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_uart_obj[uart_num]->tx_mux, (TickType_t)portMAX_DELAY);
     p_uart_obj[uart_num]->coll_det_flg = false;
     if (p_uart_obj[uart_num]->tx_buf_size > 0) {
         size_t max_size = xRingbufferGetMaxItemSize(p_uart_obj[uart_num]->tx_ring_buf);
@@ -1183,7 +1183,7 @@ static int uart_tx_all(uart_port_t uart_num, const char *src, size_t size, bool
     } else {
         while (size) {
             //semaphore for tx_fifo available
-            if (pdTRUE == xSemaphoreTake(p_uart_obj[uart_num]->tx_fifo_sem, (portTickType)portMAX_DELAY)) {
+            if (pdTRUE == xSemaphoreTake(p_uart_obj[uart_num]->tx_fifo_sem, (TickType_t)portMAX_DELAY)) {
                 uint32_t sent = 0;
                 if (UART_IS_MODE_SET(uart_num, UART_MODE_RS485_HALF_DUPLEX)) {
                     UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
@@ -1206,7 +1206,7 @@ static int uart_tx_all(uart_port_t uart_num, const char *src, size_t size, bool
             uart_hal_tx_break(&(uart_context[uart_num].hal), brk_len);
             uart_hal_ena_intr_mask(&(uart_context[uart_num].hal), UART_INTR_TX_BRK_DONE);
             UART_EXIT_CRITICAL(&(uart_context[uart_num].spinlock));
-            xSemaphoreTake(p_uart_obj[uart_num]->tx_brk_sem, (portTickType)portMAX_DELAY);
+            xSemaphoreTake(p_uart_obj[uart_num]->tx_brk_sem, (TickType_t)portMAX_DELAY);
         }
         xSemaphoreGive(p_uart_obj[uart_num]->tx_fifo_sem);
     }
@@ -1259,12 +1259,12 @@ int uart_read_bytes(uart_port_t uart_num, void *buf, uint32_t length, TickType_t
     size_t size;
     size_t copy_len = 0;
     int len_tmp;
-    if (xSemaphoreTake(p_uart_obj[uart_num]->rx_mux, (portTickType)ticks_to_wait) != pdTRUE) {
+    if (xSemaphoreTake(p_uart_obj[uart_num]->rx_mux, (TickType_t)ticks_to_wait) != pdTRUE) {
         return -1;
     }
     while (length) {
         if (p_uart_obj[uart_num]->rx_cur_remain == 0) {
-            data = (uint8_t *) xRingbufferReceive(p_uart_obj[uart_num]->rx_ring_buf, &size, (portTickType) ticks_to_wait);
+            data = (uint8_t *) xRingbufferReceive(p_uart_obj[uart_num]->rx_ring_buf, &size, (TickType_t) ticks_to_wait);
             if (data) {
                 p_uart_obj[uart_num]->rx_head_ptr = data;
                 p_uart_obj[uart_num]->rx_ptr = data;
@@ -1330,7 +1330,7 @@ esp_err_t uart_flush_input(uart_port_t uart_num)
     size_t size;
 
     //rx sem protect the ring buffer read related functions
-    xSemaphoreTake(p_uart->rx_mux, (portTickType)portMAX_DELAY);
+    xSemaphoreTake(p_uart->rx_mux, (TickType_t)portMAX_DELAY);
     UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
     uart_hal_disable_intr_mask(&(uart_context[uart_num].hal), UART_INTR_RXFIFO_FULL | UART_INTR_RXFIFO_TOUT);
     UART_EXIT_CRITICAL(&(uart_context[uart_num].spinlock));
@@ -1345,7 +1345,7 @@ esp_err_t uart_flush_input(uart_port_t uart_num)
             p_uart->rx_cur_remain = 0;
             p_uart->rx_head_ptr = NULL;
         }
-        data = (uint8_t*) xRingbufferReceive(p_uart->rx_ring_buf, &size, (portTickType) 0);
+        data = (uint8_t*) xRingbufferReceive(p_uart->rx_ring_buf, &size, (TickType_t) 0);
         if(data == NULL) {
             bool error = false;
             UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));

+ 6 - 14
components/driver/usb_serial_jtag.c

@@ -1,16 +1,8 @@
-// Copyright 2021 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #include <string.h>
 #include <stdbool.h>
@@ -146,7 +138,7 @@ int usb_serial_jtag_read_bytes(void* buf, uint32_t length, TickType_t ticks_to_w
     }
 
     // Recieve new data from ISR
-    data = (uint8_t*) xRingbufferReceiveUpTo(p_usb_serial_jtag_obj->rx_ring_buf, &data_read_len, (portTickType) ticks_to_wait, length);
+    data = (uint8_t*) xRingbufferReceiveUpTo(p_usb_serial_jtag_obj->rx_ring_buf, &data_read_len, (TickType_t) ticks_to_wait, length);
     if (data == NULL) {
         // If there is no data received from ringbuffer, return 0 directly.
         return 0;

+ 2 - 2
components/efuse/test/test_efuse.c

@@ -652,7 +652,7 @@ TEST_CASE("Test Bits are not empty. Write operation is forbidden", "[efuse]")
 
 #ifndef CONFIG_FREERTOS_UNICORE
 static const int delay_ms = 2000;
-static xSemaphoreHandle sema;
+static SemaphoreHandle_t sema;
 
 static void task1(void* arg)
 {
@@ -761,7 +761,7 @@ TEST_CASE("Check a case when ESP_ERR_DAMAGED_READING occurs and read and burn ar
 {
     cmd_stop_reset_task1 = false;
     TaskHandle_t read_task_hdl;
-    xSemaphoreHandle sema[2];
+    SemaphoreHandle_t sema[2];
     sema[0] = xSemaphoreCreateBinary();
     sema[1] = xSemaphoreCreateBinary();
 

+ 2 - 2
components/esp_gdbstub/src/gdbstub.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -507,7 +507,7 @@ static void handle_qThreadExtraInfo_command(const unsigned char *cmd, int len)
     }
     esp_gdbstub_send_start();
     esp_gdbstub_send_str_as_hex("Name: ");
-    esp_gdbstub_send_str_as_hex((const char *)pcTaskGetTaskName(handle));
+    esp_gdbstub_send_str_as_hex((const char *)pcTaskGetName(handle));
     esp_gdbstub_send_hex(' ', 8);
 
     // Current version report only Suspended state

+ 7 - 15
components/esp_hid/private/esp_hidh_private.h

@@ -1,16 +1,8 @@
-// Copyright 2017-2019 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2017-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #ifndef _ESP_HIDH_PRIVATE_H_
 #define _ESP_HIDH_PRIVATE_H_
@@ -74,8 +66,8 @@ struct esp_hidh_dev_s {
     void                    *tmp;
     size_t                  tmp_len;
 
-    xSemaphoreHandle        semaphore;
-    xSemaphoreHandle        mutex;
+    SemaphoreHandle_t        semaphore;
+    SemaphoreHandle_t        mutex;
 
     esp_err_t               (*close)        (esp_hidh_dev_t *dev);
     esp_err_t               (*report_write) (esp_hidh_dev_t *dev, size_t map_index, size_t report_id, int report_type, uint8_t *data, size_t len);

+ 1 - 1
components/esp_hid/src/ble_hidd.c

@@ -137,7 +137,7 @@ typedef struct {
 
 struct esp_ble_hidd_dev_s {
     esp_hidd_dev_t             *dev;
-    xSemaphoreHandle            sem;
+    SemaphoreHandle_t            sem;
     esp_event_loop_handle_t     event_loop_handle;
     esp_hid_device_config_t     config;
     uint16_t                    appearance;

+ 6 - 14
components/esp_hid/src/ble_hidh.c

@@ -1,16 +1,8 @@
-// Copyright 2017-2019 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2017-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #include <string.h>
 #include "ble_hidh.h"
@@ -43,7 +35,7 @@ const char *gattc_evt_str(uint8_t event)
     return s_gattc_evt_names[event];
 }
 
-static xSemaphoreHandle s_ble_hidh_cb_semaphore = NULL;
+static SemaphoreHandle_t s_ble_hidh_cb_semaphore = NULL;
 
 static inline void WAIT_CB(void)
 {

+ 1 - 1
components/esp_hid/src/esp_hidh.c

@@ -19,7 +19,7 @@ static const char *TAG = "ESP_HIDH";
 
 static esp_hidh_dev_head_t s_esp_hidh_devices;
 static esp_timer_handle_t s_esp_hidh_timer;
-static xSemaphoreHandle s_esp_hidh_devices_semaphore = NULL;
+static SemaphoreHandle_t s_esp_hidh_devices_semaphore = NULL;
 
 static void esp_hidh_dev_delay_free(void *arg);
 

+ 2 - 2
components/esp_http_server/src/port/esp32/osal.h

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2018-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2018-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -42,7 +42,7 @@ static inline void httpd_os_thread_delete(void)
 
 static inline void httpd_os_thread_sleep(int msecs)
 {
-    vTaskDelay(msecs / portTICK_RATE_MS);
+    vTaskDelay(msecs / portTICK_PERIOD_MS);
 }
 
 static inline othread_t httpd_os_thread_handle(void)

+ 11 - 11
components/esp_hw_support/test/test_dport.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -36,7 +36,7 @@ uint32_t volatile apb_intr_test_result;
 
 static void accessDPORT(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     uint32_t dport_date = DPORT_REG_READ(DPORT_DATE_REG);
 
     dport_test_result = true;
@@ -55,7 +55,7 @@ static void accessDPORT(void *pvParameters)
 
 static void accessAPB(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     uint32_t uart_date = REG_READ(UART_DATE_REG(0));
 
     apb_test_result = true;
@@ -77,7 +77,7 @@ void run_tasks(const char *task1_description, void (* task1_func)(void *), const
     apb_intr_test_result = 1;
     int i;
     TaskHandle_t th[2];
-    xSemaphoreHandle exit_sema[2];
+    SemaphoreHandle_t exit_sema[2];
 
     for (i=0; i<2; i++) {
         if((task1_func != NULL && i == 0) || (task2_func != NULL && i == 1)){
@@ -172,7 +172,7 @@ static uint32_t apb_counter;
 
 static void accessDPORT_stall_other_cpu(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     uint32_t dport_date = DPORT_REG_READ(DPORT_DATE_REG);
     uint32_t dport_date_cur;
     dport_test_result = true;
@@ -195,7 +195,7 @@ static void accessDPORT_stall_other_cpu(void *pvParameters)
 
 static void accessAPB_measure_performance(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     uint32_t uart_date = REG_READ(UART_DATE_REG(0));
 
     apb_test_result = true;
@@ -215,7 +215,7 @@ static void accessAPB_measure_performance(void *pvParameters)
 
 static void accessDPORT_pre_reading_apb(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     uint32_t dport_date = DPORT_REG_READ(DPORT_DATE_REG);
     uint32_t dport_date_cur;
     dport_test_result = true;
@@ -346,7 +346,7 @@ uint32_t xt_highint5_read_apb;
 
 #ifndef CONFIG_FREERTOS_UNICORE
 intr_handle_t inth;
-xSemaphoreHandle sync_sema;
+SemaphoreHandle_t sync_sema;
 
 static void init_hi_interrupt(void *arg)
 {
@@ -360,7 +360,7 @@ static void init_hi_interrupt(void *arg)
 
 static void accessDPORT2_stall_other_cpu(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     dport_test_result = true;
     while (exit_flag == false) {
         DPORT_STALL_OTHER_CPU_START();
@@ -395,7 +395,7 @@ TEST_CASE("Check stall workaround DPORT and Hi-interrupt", "[esp32]")
 
 static void accessDPORT2(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     dport_test_result = true;
 
     TEST_ESP_OK(esp_intr_alloc(ETS_INTERNAL_TIMER2_INTR_SOURCE, ESP_INTR_FLAG_LEVEL5 | ESP_INTR_FLAG_IRAM, NULL, NULL, &inth));
@@ -471,7 +471,7 @@ static uint32_t IRAM_ATTR test_dport_access_reg_read(uint32_t reg)
 // The accessDPORT3 task is similar accessDPORT2 but uses test_dport_access_reg_read() instead of usual DPORT_REG_READ().
 static void accessDPORT3(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     dport_test_result = true;
 
     TEST_ESP_OK(esp_intr_alloc(ETS_INTERNAL_TIMER2_INTR_SOURCE, ESP_INTR_FLAG_LEVEL5 | ESP_INTR_FLAG_IRAM, NULL, NULL, &inth));

+ 1 - 1
components/esp_hw_support/test/test_intr_alloc.c

@@ -247,7 +247,7 @@ void isr_alloc_free_test(void)
     }
     TEST_ASSERT(ret == ESP_OK);
     xTaskCreatePinnedToCore(isr_free_task, "isr_free_task", 1024 * 2, (void *)&test_handle, 10, NULL, !xPortGetCoreID());
-    vTaskDelay(1000 / portTICK_RATE_MS);
+    vTaskDelay(1000 / portTICK_PERIOD_MS);
     TEST_ASSERT(test_handle == NULL);
     printf("test passed\n");
 }

+ 6 - 14
components/esp_netif/esp_netif_objects.c

@@ -1,16 +1,8 @@
-// Copyright 2015-2019 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #include "esp_netif.h"
 #include "sys/queue.h"
@@ -36,7 +28,7 @@ struct slist_netifs_s {
 SLIST_HEAD(slisthead, slist_netifs_s) s_head = { .slh_first = NULL, };
 
 static size_t s_esp_netif_counter = 0;
-static xSemaphoreHandle  s_list_lock = NULL;
+static SemaphoreHandle_t  s_list_lock = NULL;
 
 ESP_EVENT_DEFINE_BASE(IP_EVENT);
 

+ 1 - 1
components/esp_ringbuf/test/test_ringbuf.c

@@ -634,7 +634,7 @@ static void queue_set_receiving_task(void *queue_set_handle)
     int no_of_items = BUFFER_SIZE / SMALL_ITEM_SIZE;
     int items_rec_count[NO_OF_RB_TYPES] = {0};
     while (done != pdTRUE) {
-        xQueueSetMemberHandle member = xQueueSelectFromSet(queue_set, TIMEOUT_TICKS);
+        QueueSetMemberHandle_t member = xQueueSelectFromSet(queue_set, TIMEOUT_TICKS);
         //Read from selected ring buffer
         if (xRingbufferCanRead(buffer_handles[0], member) == pdTRUE) {
             //No-split buffer

+ 2 - 2
components/esp_system/port/arch/xtensa/panic_arch.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -146,7 +146,7 @@ static void print_debug_exception_details(const void *f)
             }
 #endif
 
-            const char *name = pcTaskGetTaskName(xTaskGetCurrentTaskHandleForCPU(core));
+            const char *name = pcTaskGetName(xTaskGetCurrentTaskHandleForCPU(core));
             panic_print_str("Stack canary watchpoint triggered (");
             panic_print_str(name);
             panic_print_str(") ");

+ 2 - 2
components/esp_system/task_wdt.c

@@ -158,12 +158,12 @@ static void task_wdt_isr(void *arg)
             if (xTaskGetAffinity(twdttask->task_handle)==tskNO_AFFINITY) {
                 cpu=DRAM_STR("CPU 0/1");
             }
-            ESP_EARLY_LOGE(TAG, " - %s (%s)", pcTaskGetTaskName(twdttask->task_handle), cpu);
+            ESP_EARLY_LOGE(TAG, " - %s (%s)", pcTaskGetName(twdttask->task_handle), cpu);
         }
     }
     ESP_EARLY_LOGE(TAG, "%s", DRAM_STR("Tasks currently running:"));
     for (int x=0; x<portNUM_PROCESSORS; x++) {
-        ESP_EARLY_LOGE(TAG, "CPU %d: %s", x, pcTaskGetTaskName(xTaskGetCurrentTaskHandleForCPU(x)));
+        ESP_EARLY_LOGE(TAG, "CPU %d: %s", x, pcTaskGetName(xTaskGetCurrentTaskHandleForCPU(x)));
     }
 
     esp_task_wdt_isr_user_handler();

+ 6 - 6
components/esp_system/test/test_ipc.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -52,7 +52,7 @@ static void test_func_ipc(void *sema)
 {
     esp_rom_delay_us(1000000 + xPortGetCoreID() * 100);
     func_ipc_priority = uxTaskPriorityGet(NULL);
-    xSemaphoreGive(*(xSemaphoreHandle *)sema);
+    xSemaphoreGive(*(SemaphoreHandle_t *)sema);
     esp_rom_printf("test_func_ipc: [%d, %d]\n", func_ipc_priority, xPortGetCoreID());
 }
 
@@ -62,7 +62,7 @@ TEST_CASE("Test ipc_task works with the priority of the caller's task", "[ipc]")
     func_ipc_priority = 0;
     vTaskPrioritySet(NULL, priority);
 
-    xSemaphoreHandle sema_ipc_done = xSemaphoreCreateBinary();
+    SemaphoreHandle_t sema_ipc_done = xSemaphoreCreateBinary();
 
     exit_flag = false;
     xTaskCreatePinnedToCore(task1, "task1", 4096, NULL, priority + 2, NULL, 1);
@@ -93,9 +93,9 @@ static void task(void *sema)
 {
     int priority = uxTaskPriorityGet(NULL);
     ESP_LOGI("task", "start [priority = %d, cpu = %d]", priority, xPortGetCoreID());
-    xSemaphoreTake(*(xSemaphoreHandle *)sema, portMAX_DELAY);
+    xSemaphoreTake(*(SemaphoreHandle_t *)sema, portMAX_DELAY);
     esp_ipc_call_blocking(!xPortGetCoreID(), test_func2_ipc, &priority);
-    xSemaphoreGive(*(xSemaphoreHandle *)sema);
+    xSemaphoreGive(*(SemaphoreHandle_t *)sema);
     ESP_LOGI("task", "finish [priority = %d, cpu = %d]", priority, xPortGetCoreID());
     vTaskDelete(NULL);
 }
@@ -105,7 +105,7 @@ TEST_CASE("Test multiple ipc_calls", "[ipc]")
     const int max_tasks = 5;
     UBaseType_t priority = uxTaskPriorityGet(NULL);
     ESP_LOGI("test", "priority = %d, cpu = %d", priority, xPortGetCoreID());
-    xSemaphoreHandle sema_ipc_done[max_tasks * portNUM_PROCESSORS];
+    SemaphoreHandle_t sema_ipc_done[max_tasks * portNUM_PROCESSORS];
 
     for (int task_num = 0; task_num < max_tasks; ++task_num) {
         ++priority;

+ 3 - 3
components/esp_system/test/test_ipc_isr.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -54,7 +54,7 @@ static bool volatile s_stop;
 
 static void task_asm(void *arg)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) arg;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) arg;
     int val;
     int counter = 0;
     printf("task_asm\n");
@@ -72,7 +72,7 @@ static void task_asm(void *arg)
 
 TEST_CASE("Test ipc_isr two tasks use IPC function calls", "[ipc]")
 {
-    xSemaphoreHandle exit_sema[2];
+    SemaphoreHandle_t exit_sema[2];
     exit_sema[0] = xSemaphoreCreateBinary();
     exit_sema[1] = xSemaphoreCreateBinary();
     s_stop = false;

+ 2 - 2
components/esp_system/test/test_sleep.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2019-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -514,7 +514,7 @@ static void trigger_deepsleep(void)
     esp_set_time_from_rtc();
 
     // Delay for time error accumulation.
-    vTaskDelay(10000/portTICK_RATE_MS);
+    vTaskDelay(10000/portTICK_PERIOD_MS);
 
     // Save start time. Deep sleep.
     gettimeofday(&start, NULL);

+ 3 - 3
components/esp_websocket_client/esp_websocket_client.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -105,7 +105,7 @@ struct esp_websocket_client {
     bool                        run;
     bool                        wait_for_pong_resp;
     EventGroupHandle_t          status_bits;
-    xSemaphoreHandle            lock;
+    SemaphoreHandle_t            lock;
     char                        *rx_buffer;
     char                        *tx_buffer;
     int                         buffer_size;
@@ -696,7 +696,7 @@ static void esp_websocket_client_task(void *pv)
             }
         } else if (WEBSOCKET_STATE_WAIT_TIMEOUT == client->state) {
             // waiting for reconnecting...
-            vTaskDelay(client->wait_timeout_ms / 2 / portTICK_RATE_MS);
+            vTaskDelay(client->wait_timeout_ms / 2 / portTICK_PERIOD_MS);
         } else if (WEBSOCKET_STATE_CLOSING == client->state &&
                   (CLOSE_FRAME_SENT_BIT & xEventGroupGetBits(client->status_bits))) {
             ESP_LOGD(TAG, " Waiting for TCP connection to be closed by the server");

+ 4 - 4
components/esp_wifi/src/smartconfig_ack.c

@@ -103,7 +103,7 @@ static void sc_ack_send_task(void *pvParameters)
 
     esp_wifi_get_mac(WIFI_IF_STA, ack->ctx.mac);
 
-    vTaskDelay(200 / portTICK_RATE_MS);
+    vTaskDelay(200 / portTICK_PERIOD_MS);
 
     while (s_sc_ack_send) {
         /* Get local IP address of station */
@@ -171,13 +171,13 @@ static void sc_ack_send_task(void *pvParameters)
 
             while (s_sc_ack_send) {
                 /* Send smartconfig ACK every 100ms. */
-                vTaskDelay(100 / portTICK_RATE_MS);
+                vTaskDelay(100 / portTICK_PERIOD_MS);
 
                 sendlen = sendto(send_sock, &ack->ctx, ack_len, 0, (struct sockaddr*) &server_addr, sin_size);
                 if (sendlen <= 0) {
                     err = sc_ack_send_get_errno(send_sock);
                     ESP_LOGD(TAG, "send failed, errno %d", err);
-                    vTaskDelay(100 / portTICK_RATE_MS);
+                    vTaskDelay(100 / portTICK_PERIOD_MS);
                 }
 
                 /*  Send 30 smartconfig ACKs. Then smartconfig is successful. */
@@ -188,7 +188,7 @@ static void sc_ack_send_task(void *pvParameters)
             }
         }
         else {
-            vTaskDelay((portTickType)(100 / portTICK_RATE_MS));
+            vTaskDelay((TickType_t)(100 / portTICK_PERIOD_MS));
         }
     }
 

+ 3 - 3
components/esp_wifi/test/test_wifi.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  *
@@ -299,7 +299,7 @@ static void wifi_connect_by_bssid(uint8_t *bssid)
     TEST_ESP_OK(esp_wifi_set_config(WIFI_IF_STA, &w_config));
     TEST_ESP_OK(esp_wifi_connect());
     ESP_LOGI(TAG, "called esp_wifi_connect()");
-    bits = xEventGroupWaitBits(wifi_events, GOT_IP_EVENT, 1, 0, 7000/portTICK_RATE_MS);
+    bits = xEventGroupWaitBits(wifi_events, GOT_IP_EVENT, 1, 0, 7000/portTICK_PERIOD_MS);
     TEST_ASSERT(bits == GOT_IP_EVENT);
 }
 
@@ -321,7 +321,7 @@ static void test_wifi_connection_sta(void)
 
     unity_send_signal("STA connected");
 
-    bits = xEventGroupWaitBits(wifi_events, DISCONNECT_EVENT, 1, 0, 60000 / portTICK_RATE_MS);
+    bits = xEventGroupWaitBits(wifi_events, DISCONNECT_EVENT, 1, 0, 60000 / portTICK_PERIOD_MS);
     // disconnect event not triggered
     printf("wait finish\n");
     TEST_ASSERT(bits == 0);

+ 6 - 14
components/espcoredump/src/core_dump_elf.c

@@ -1,16 +1,8 @@
-// Copyright 2015-2019 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 #include <string.h>
 #include "esp_attr.h"
 #include "esp_partition.h"
@@ -698,7 +690,7 @@ static void elf_parse_version_info(esp_core_dump_summary_t *summary, void *data)
 static void elf_parse_exc_task_name(esp_core_dump_summary_t *summary, void *tcb_data)
 {
     StaticTask_t *tcb = (StaticTask_t *) tcb_data;
-    /* An ugly way to get the task name. We could possibly use pcTaskGetTaskName here.
+    /* An ugly way to get the task name. We could possibly use pcTaskGetName here.
      * But that has assumption that TCB pointer can be used as TaskHandle. So let's
      * keep it this way. */
     memset(summary->exc_task, 0, sizeof(summary->exc_task));

+ 3 - 3
components/espcoredump/test_apps/main/test_core_dump.c

@@ -40,7 +40,7 @@ void bad_ptr_task(void *pvParameter)
 {
     printf("Task 'bad_ptr_task' start.\n");
     while (1) {
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         printf("Task 'bad_ptr_task' run.\n");
         bad_ptr_func();
     }
@@ -75,7 +75,7 @@ void unaligned_ptr_task(void *pvParameter)
 {
     printf("Task 'unaligned_ptr_task' start.\n");
     while (1) {
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         printf("Task 'unaligned_ptr_task' run.\n");
         recur_func();
     }
@@ -86,7 +86,7 @@ void failed_assert_task(void *pvParameter)
 {
     printf("Task 'failed_assert_task' start.\n");
     while (1) {
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         printf("Task 'failed_assert_task' run.\n");
         if(crash_flags & TCI_FAIL_ASSERT) {
             printf("Assert.\n");

+ 3 - 3
components/freemodbus/port/portevent.c

@@ -3,7 +3,7 @@
  *
  * SPDX-License-Identifier: BSD-3-Clause
  *
- * SPDX-FileContributor: 2016-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileContributor: 2016-2022 Espressif Systems (Shanghai) CO LTD
  */
 /*
  * FreeModbus Libary: ESP32 Port Demo Application
@@ -47,7 +47,7 @@
 #include "sdkconfig.h"
 #include "port_serial_slave.h"
 /* ----------------------- Variables ----------------------------------------*/
-static xQueueHandle xQueueHdl;
+static QueueHandle_t xQueueHdl;
 
 #define MB_EVENT_QUEUE_SIZE     (6)
 #define MB_EVENT_QUEUE_TIMEOUT  (pdMS_TO_TICKS(CONFIG_FMB_EVENT_QUEUE_TIMEOUT))
@@ -113,7 +113,7 @@ xMBPortEventGet(eMBEventType * peEvent)
     return xEventHappened;
 }
 
-xQueueHandle
+QueueHandle_t
 xMBPortEventGetHandle(void)
 {
     if(xQueueHdl != NULL)

+ 5 - 5
components/freemodbus/tcp_slave/port/port_tcp_slave.c

@@ -87,19 +87,19 @@ static void vxMBTCPPortMStoTimeVal(USHORT usTimeoutMs, struct timeval *pxTimeout
     pxTimeout->tv_usec = (usTimeoutMs - (pxTimeout->tv_sec * 1000)) * 1000;
 }
 
-static xQueueHandle xMBTCPPortRespQueueCreate(void)
+static QueueHandle_t xMBTCPPortRespQueueCreate(void)
 {
-    xQueueHandle xRespQueueHandle = xQueueCreate(2, sizeof(void*));
+    QueueHandle_t xRespQueueHandle = xQueueCreate(2, sizeof(void*));
     MB_PORT_CHECK((xRespQueueHandle != NULL), NULL, "TCP respond queue creation failure.");
     return xRespQueueHandle;
 }
 
-static void vMBTCPPortRespQueueDelete(xQueueHandle xRespQueueHandle)
+static void vMBTCPPortRespQueueDelete(QueueHandle_t xRespQueueHandle)
 {
     vQueueDelete(xRespQueueHandle);
 }
 
-static void* vxMBTCPPortRespQueueRecv(xQueueHandle xRespQueueHandle)
+static void* vxMBTCPPortRespQueueRecv(QueueHandle_t xRespQueueHandle)
 {
     void* pvResp = NULL;
     MB_PORT_CHECK(xRespQueueHandle != NULL, NULL, "Response queue is not initialized.");
@@ -111,7 +111,7 @@ static void* vxMBTCPPortRespQueueRecv(xQueueHandle xRespQueueHandle)
     return pvResp;
 }
 
-static BOOL vxMBTCPPortRespQueueSend(xQueueHandle xRespQueueHandle, void* pvResp)
+static BOOL vxMBTCPPortRespQueueSend(QueueHandle_t xRespQueueHandle, void* pvResp)
 {
     MB_PORT_CHECK(xRespQueueHandle != NULL, FALSE, "Response queue is not initialized.");
     BaseType_t xStatus = xQueueSend(xConfig.xRespQueueHandle,

+ 2 - 2
components/freemodbus/tcp_slave/port/port_tcp_slave.h

@@ -3,7 +3,7 @@
  *
  * SPDX-License-Identifier: BSD-3-Clause
  *
- * SPDX-FileContributor: 2016-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileContributor: 2016-2022 Espressif Systems (Shanghai) CO LTD
  */
 /*
  * FreeModbus Libary: ESP32 TCP Port
@@ -76,7 +76,7 @@ typedef struct {
 
 typedef struct {
     TaskHandle_t xMbTcpTaskHandle;      /*!< Server task handle */
-    xQueueHandle xRespQueueHandle;      /*!< Response queue handle */
+    QueueHandle_t xRespQueueHandle;      /*!< Response queue handle */
     MbClientInfo_t* pxCurClientInfo;    /*!< Current client info */
     MbClientInfo_t** pxMbClientInfo;    /*!< Pointers to information about connected clients */
     USHORT usPort;                      /*!< TCP/UDP port number */

+ 1 - 1
components/freertos/FreeRTOS-Kernel/portable/xtensa/port.c

@@ -140,7 +140,7 @@ static void vPortTaskWrapper(TaskFunction_t pxCode, void *pvParameters)
 {
     pxCode(pvParameters);
     //FreeRTOS tasks should not return. Log the task name and abort.
-    char *pcTaskName = pcTaskGetTaskName(NULL);
+    char *pcTaskName = pcTaskGetName(NULL);
     ESP_LOGE("FreeRTOS", "FreeRTOS Task \"%s\" should not return, Aborting now!", pcTaskName);
     abort();
 }

+ 7 - 0
components/freertos/Kconfig

@@ -219,6 +219,13 @@ menu "FreeRTOS"
 
             For most uses, the default of 16 is OK.
 
+    config FREERTOS_ENABLE_BACKWARD_COMPATIBILITY
+        bool "Support legacy FreeRTOS API"
+        default n
+        help
+            This option enables the configENABLE_BACKWARD_COMPATIBILITY option, thus allowing the usage
+            of legacy function names and types present in versions prior to FreeRTOS v8.0.0.
+
     config FREERTOS_SUPPORT_STATIC_ALLOCATION
         # Always enabled.
         # Kconfig option preserved for compatibility with code

+ 6 - 0
components/freertos/esp_additions/include/freertos/FreeRTOSConfig.h

@@ -191,6 +191,12 @@
 #define configUSE_NEWLIB_REENTRANT                      1
 #endif
 
+#if CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY
+#define configENABLE_BACKWARD_COMPATIBILITY             1
+#else
+#define configENABLE_BACKWARD_COMPATIBILITY             0
+#endif
+
 #define configSUPPORT_DYNAMIC_ALLOCATION                1
 #define configSUPPORT_STATIC_ALLOCATION                 1
 

+ 6 - 1
components/freertos/test/test_spinlocks.c

@@ -1,3 +1,8 @@
+/*
+ * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 /*
  Combined unit tests & benchmarking for spinlock "portMUX" functionality
 */
@@ -73,7 +78,7 @@ TEST_CASE("portMUX recursive locks (no contention)", "[freertos]")
 
 static volatile int shared_value;
 static portMUX_TYPE shared_mux;
-static xSemaphoreHandle done_sem;
+static SemaphoreHandle_t done_sem;
 
 static void task_shared_value_increment(void *ignore)
 {

+ 2 - 2
components/lwip/port/esp32/freertos/sys_arch.c

@@ -184,7 +184,7 @@ sys_arch_sem_wait(sys_sem_t *sem, u32_t timeout)
     ret = xSemaphoreTake(*sem, portMAX_DELAY);
     LWIP_ASSERT("taking semaphore failed", ret == pdTRUE);
   } else {
-    TickType_t timeout_ticks = timeout / portTICK_RATE_MS;
+    TickType_t timeout_ticks = timeout / portTICK_PERIOD_MS;
     ret = xSemaphoreTake(*sem, timeout_ticks);
     if (ret == errQUEUE_EMPTY) {
       /* timed out */
@@ -326,7 +326,7 @@ sys_arch_mbox_fetch(sys_mbox_t *mbox, void **msg, u32_t timeout)
     ret = xQueueReceive((*mbox)->os_mbox, &(*msg), portMAX_DELAY);
     LWIP_ASSERT("mbox fetch failed", ret == pdTRUE);
   } else {
-    TickType_t timeout_ticks = timeout / portTICK_RATE_MS;
+    TickType_t timeout_ticks = timeout / portTICK_PERIOD_MS;
     ret = xQueueReceive((*mbox)->os_mbox, &(*msg), timeout_ticks);
     if (ret == errQUEUE_EMPTY) {
       /* timed out */

+ 1 - 1
components/mbedtls/test/test_aes.c

@@ -1477,7 +1477,7 @@ TEST_CASE("mbedtls AES external flash tests", "[aes]")
 #if CONFIG_ESP_SYSTEM_RTC_FAST_MEM_AS_HEAP_DEPCHECK
 
 RTC_FAST_ATTR uint8_t rtc_stack[4096];
-static xSemaphoreHandle done_sem;
+static SemaphoreHandle_t done_sem;
 
 static void aes_ctr_stream_test_task(void *pv)
 {

+ 1 - 1
components/mbedtls/test/test_aes_sha_parallel.c

@@ -11,7 +11,7 @@
 #include "freertos/task.h"
 #include "freertos/semphr.h"
 
-static xSemaphoreHandle done_sem;
+static SemaphoreHandle_t done_sem;
 
 static const unsigned char *one_hundred_bs =  (unsigned char *)
         "bbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbbb";

+ 10 - 10
components/mbedtls/test/test_aes_sha_rsa.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -33,7 +33,7 @@ static volatile bool exit_flag = false;
 
 static void aes_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     ESP_LOGI(TAG, "aes_task is started");
     esp_aes_context ctx = {
             .key_bytes = 16,
@@ -55,7 +55,7 @@ static void aes_task(void *pvParameters)
 
 static void sha_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     ESP_LOGI(TAG, "sha_task is started");
     const char *input = "Space!#$%&()*+,-.0123456789:;<=>?@ABCDEFGHIJKLMNOPQRSTUVWXYZ[]^_abcdefghijklmnopqrstuvwxyz~DEL0123456789";
     unsigned char output[64];
@@ -73,7 +73,7 @@ static void sha_task(void *pvParameters)
 
 static void mbedtls_sha256_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     ESP_LOGI(TAG, "mbedtls_sha256_task is started");
     const char *input = "@ABCDEFGHIJKLMNOPQRSTUVWXYZ[]^_abcdefghijklmnopqrstuvwxyz~DEL0123456789Space!#$%&()*+,-.0123456789:;<=>?";
     mbedtls_sha256_context sha256_ctx;
@@ -111,7 +111,7 @@ TEST_CASE("Test shared using AES SHA512 SHA256", "[hw_crypto]")
 #else
     const int max_tasks = 3;
 #endif
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
@@ -145,7 +145,7 @@ TEST_CASE("Test shared using AES SHA512 SHA256", "[hw_crypto]")
 
 static void rsa_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     ESP_LOGI(TAG, "rsa_task is started");
     while (exit_flag == false) {
         mbedtls_rsa_self_test(0);
@@ -161,7 +161,7 @@ TEST_CASE("Test shared using AES RSA", "[hw_crypto]")
 #else
     const int max_tasks = 2;
 #endif
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
@@ -195,7 +195,7 @@ TEST_CASE("Test shared using SHA512 RSA", "[hw_crypto]")
 #else
     const int max_tasks = 2;
 #endif
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
@@ -229,7 +229,7 @@ TEST_CASE("Test shared using SHA256 RSA", "[hw_crypto]")
 #else
     const int max_tasks = 2;
 #endif
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
@@ -263,7 +263,7 @@ TEST_CASE("Test shared using AES SHA RSA", "[hw_crypto]")
 #else
     const int max_tasks = 3;
 #endif
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();

+ 2 - 2
components/mbedtls/test/test_esp_crt_bundle.c

@@ -160,7 +160,7 @@ void server_task(void *pvParameters)
 {
     int ret;
     mbedtls_endpoint_t server;
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
 
 
     if (server_setup(&server) != ESP_OK) {
@@ -320,7 +320,7 @@ TEST_CASE("custom certificate bundle", "[mbedtls]")
 
    test_case_uses_tcpip();
 
-   xSemaphoreHandle signal_sem = xSemaphoreCreateBinary();
+   SemaphoreHandle_t signal_sem = xSemaphoreCreateBinary();
    TEST_ASSERT_NOT_NULL(signal_sem);
 
    exit_flag = false;

+ 3 - 3
components/mbedtls/test/test_mbedtls_sha.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -95,7 +95,7 @@ TEST_CASE("mbedtls SHA interleaving", "[mbedtls]")
     TEST_ASSERT_EQUAL_MEMORY_MESSAGE(sha1_thousand_as, sha1, 20, "SHA1 calculation");
 }
 
-static xSemaphoreHandle done_sem;
+static SemaphoreHandle_t done_sem;
 static void tskRunSHA1Test(void *pvParameters)
 {
     mbedtls_sha1_context sha1_ctx;
@@ -523,7 +523,7 @@ TEST_CASE("mbedtls SHA256 PSRAM DMA", "[mbedtls]")
 
 extern RTC_FAST_ATTR uint8_t rtc_stack[4096];
 
-static xSemaphoreHandle done_sem;
+static SemaphoreHandle_t done_sem;
 
 TEST_CASE("mbedtls SHA stack in RTC RAM", "[mbedtls]")
 {

+ 5 - 17
components/mdns/host_test/components/freertos_linux/include/freertos/FreeRTOS.h

@@ -1,16 +1,8 @@
-// Copyright 2021 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 #pragma once
 
 #include <stdint.h>
@@ -21,13 +13,10 @@
 #define portTICK_PERIOD_MS 1
 #define portMAX_DELAY ( TickType_t ) 0xffffffffUL
 
-typedef void * xSemaphoreHandle;
 typedef void * SemaphoreHandle_t;
-typedef void * xQueueHandle;
 typedef void * QueueHandle_t;
 typedef void * TaskHandle_t;
 typedef uint32_t TickType_t;
-typedef uint32_t portTickType;
 
 typedef void (*TaskFunction_t)( void * );
 typedef unsigned int	UBaseType_t;
@@ -39,7 +28,6 @@ typedef int 			BaseType_t;
 #define pdPASS			( pdTRUE )
 #define pdFAIL			( pdFALSE )
 
-#define portTICK_RATE_MS portTICK_PERIOD_MS
 #define pdMS_TO_TICKS(tick)    (tick)
 
 uint32_t esp_get_free_heap_size(void);

+ 6 - 14
components/mdns/host_test/components/freertos_linux/include/freertos/task.h

@@ -1,21 +1,13 @@
-// Copyright 2021 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.
-// You may obtain a copy of the License at
-
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 #pragma once
 
 #include "freertos/FreeRTOS.h"
 
-#define xTaskHandle TaskHandle_t
+#define TaskHandle_t TaskHandle_t
 #define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( QueueHandle_t ) ( xSemaphore ) )
 
 void vTaskDelay( const TickType_t xTicksToDelay );

+ 19 - 19
components/mdns/mdns.c

@@ -238,7 +238,7 @@ esp_err_t _mdns_send_rx_action(mdns_rx_packet_t * packet)
 
     action->type = ACTION_RX_HANDLE;
     action->data.rx_handle.packet = packet;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
         return ESP_ERR_NO_MEM;
     }
@@ -4672,7 +4672,7 @@ static esp_err_t _mdns_send_search_action(mdns_action_type_t type, mdns_search_o
 
     action->type = type;
     action->data.search_add.search = search;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
         return ESP_ERR_NO_MEM;
     }
@@ -4706,7 +4706,7 @@ static void _mdns_scheduler_run(void)
             action->type = ACTION_TX_HANDLE;
             action->data.tx_handle.packet = p;
             p->queued = true;
-            if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+            if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
                 free(action);
                 p->queued = false;
             }
@@ -4854,7 +4854,7 @@ static esp_err_t _mdns_service_task_stop(void)
         mdns_action_t action;
         mdns_action_t * a = &action;
         action.type = ACTION_TASK_STOP;
-        if (xQueueSend(_mdns_server->action_queue, &a, (portTickType)0) != pdPASS) {
+        if (xQueueSend(_mdns_server->action_queue, &a, (TickType_t)0) != pdPASS) {
             vTaskDelete(_mdns_service_task_handle);
             _mdns_service_task_handle = NULL;
         }
@@ -4897,7 +4897,7 @@ static void event_handler(void* arg, esp_event_base_t event_base,
         action->data.sys_event.interface = event->esp_netif;
     }
 
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
     }
 }
@@ -5056,7 +5056,7 @@ esp_err_t mdns_hostname_set(const char * hostname)
     action->type = ACTION_HOSTNAME_SET;
     action->data.hostname_set.hostname = new_hostname;
     action->data.hostname_set.calling_task = xTaskGetCurrentTaskHandle();
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(new_hostname);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5087,7 +5087,7 @@ esp_err_t mdns_delegate_hostname_add(const char * hostname, const mdns_ip_addr_t
     action->type = ACTION_DELEGATE_HOSTNAME_ADD;
     action->data.delegate_hostname.hostname = new_hostname;
     action->data.delegate_hostname.address_list = copy_address_list(address_list);
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(new_hostname);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5116,7 +5116,7 @@ esp_err_t mdns_delegate_hostname_remove(const char * hostname)
     }
     action->type = ACTION_DELEGATE_HOSTNAME_REMOVE;
     action->data.delegate_hostname.hostname = new_hostname;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(new_hostname);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5150,7 +5150,7 @@ esp_err_t mdns_instance_name_set(const char * instance)
     }
     action->type = ACTION_INSTANCE_SET;
     action->data.instance = new_instance;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(new_instance);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5202,7 +5202,7 @@ esp_err_t mdns_service_add_for_host(const char * instance, const char * service,
     }
     action->type = ACTION_SERVICE_ADD;
     action->data.srv_add.service = item;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         _mdns_free_service(s);
         free(item);
         free(action);
@@ -5216,7 +5216,7 @@ esp_err_t mdns_service_add_for_host(const char * instance, const char * service,
         if (expired >= timeout_ticks) {
             return ESP_FAIL; // Timeout
         }
-        vTaskDelay(MIN(10 / portTICK_RATE_MS, timeout_ticks - expired));
+        vTaskDelay(MIN(10 / portTICK_PERIOD_MS, timeout_ticks - expired));
     }
 
     return ESP_OK;
@@ -5260,7 +5260,7 @@ esp_err_t mdns_service_port_set_for_host(const char *instance, const char * serv
     action->type = ACTION_SERVICE_PORT_SET;
     action->data.srv_port.service = s;
     action->data.srv_port.port = port;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
         return ESP_ERR_NO_MEM;
     }
@@ -5304,7 +5304,7 @@ esp_err_t mdns_service_txt_set_for_host(const char * instance, const char * serv
     action->data.srv_txt_replace.service = s;
     action->data.srv_txt_replace.txt = new_txt;
 
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         _mdns_free_linked_txt(new_txt);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5358,7 +5358,7 @@ esp_err_t mdns_service_txt_item_set_for_host_with_explicit_value_len(const char
         action->data.srv_txt_set.value = NULL;
         action->data.srv_txt_set.value_len = 0;
     }
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action->data.srv_txt_set.key);
         free(action->data.srv_txt_set.value);
         free(action);
@@ -5417,7 +5417,7 @@ esp_err_t mdns_service_txt_item_remove_for_host(const char * instance, const cha
         free(action);
         return ESP_ERR_NO_MEM;
     }
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action->data.srv_txt_del.key);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5458,7 +5458,7 @@ esp_err_t mdns_service_subtype_add_for_host(const char *instance_name, const cha
         free(action);
         return ESP_ERR_NO_MEM;
     }
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action->data.srv_subtype_add.subtype);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5493,7 +5493,7 @@ esp_err_t mdns_service_instance_name_set_for_host(const char * instance_old, con
     action->type = ACTION_SERVICE_INSTANCE_SET;
     action->data.srv_instance.service = s;
     action->data.srv_instance.instance = new_instance;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(new_instance);
         free(action);
         return ESP_ERR_NO_MEM;
@@ -5526,7 +5526,7 @@ esp_err_t mdns_service_remove_for_host(const char * instance, const char * servi
     }
     action->type = ACTION_SERVICE_DEL;
     action->data.srv_del.service = s;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
         return ESP_ERR_NO_MEM;
     }
@@ -5556,7 +5556,7 @@ esp_err_t mdns_service_remove_all(void)
         return ESP_ERR_NO_MEM;
     }
     action->type = ACTION_SERVICES_CLEAR;
-    if (xQueueSend(_mdns_server->action_queue, &action, (portTickType)0) != pdPASS) {
+    if (xQueueSend(_mdns_server->action_queue, &action, (TickType_t)0) != pdPASS) {
         free(action);
         return ESP_ERR_NO_MEM;
     }

+ 1 - 1
components/mdns/private_include/mdns_private.h

@@ -396,7 +396,7 @@ typedef struct {
     union {
         struct {
             char * hostname;
-            xTaskHandle calling_task;
+            TaskHandle_t calling_task;
         } hostname_set;
         char * instance;
         struct {

+ 2 - 5
components/mdns/test_afl_fuzz_host/esp32_mock.h

@@ -53,7 +53,7 @@
 #define INC_TASK_H
 
 #define pdMS_TO_TICKS(a) a
-#define portTICK_RATE_MS 10
+#define portTICK_PERIOD_MS 10
 #define xSemaphoreTake(s,d)        true
 #define xTaskDelete(a)
 #define vTaskDelete(a)             free(a)
@@ -73,19 +73,16 @@
 #define ESP_TASK_PRIO_MAX 25
 #define ESP_TASKD_EVENT_PRIO 5
 #define _mdns_udp_pcb_write(tcpip_if, ip_protocol, ip, port, data, len) len
-#define xTaskHandle TaskHandle_t
+#define TaskHandle_t TaskHandle_t
 
 
 typedef int32_t esp_err_t;
 
-typedef void * xSemaphoreHandle;
 typedef void * SemaphoreHandle_t;
-typedef void * xQueueHandle;
 typedef void * QueueHandle_t;
 typedef void * TaskHandle_t;
 typedef int    BaseType_t;
 typedef uint32_t TickType_t;
-typedef uint32_t portTickType;
 
 
 extern const char * WIFI_EVENT;

+ 6 - 6
components/newlib/locks.c

@@ -17,7 +17,7 @@
 /* Notes on our newlib lock implementation:
  *
  * - Use FreeRTOS mutex semaphores as locks.
- * - lock_t is int, but we store an xSemaphoreHandle there.
+ * - lock_t is int, but we store an SemaphoreHandle_t there.
  * - Locks are no-ops until the FreeRTOS scheduler is running.
  * - Due to this, locks need to be lazily initialised the first time
  *   they are acquired. Initialisation/deinitialisation of locks is
@@ -61,7 +61,7 @@ static void IRAM_ATTR lock_init_generic(_lock_t *lock, uint8_t mutex_type) {
            without writing wrappers. Doing it this way seems much less
            spaghetti-like.
         */
-        xSemaphoreHandle new_sem = xQueueCreateMutex(mutex_type);
+        SemaphoreHandle_t new_sem = xQueueCreateMutex(mutex_type);
         if (!new_sem) {
             abort(); /* No more semaphores available or OOM */
         }
@@ -93,7 +93,7 @@ void IRAM_ATTR _lock_init_recursive(_lock_t *lock) {
 void IRAM_ATTR _lock_close(_lock_t *lock) {
     portENTER_CRITICAL(&lock_init_spinlock);
     if (*lock) {
-        xSemaphoreHandle h = (xSemaphoreHandle)(*lock);
+        SemaphoreHandle_t h = (SemaphoreHandle_t)(*lock);
 #if (INCLUDE_xSemaphoreGetMutexHolder == 1)
         configASSERT(xSemaphoreGetMutexHolder(h) == NULL); /* mutex should not be held */
 #endif
@@ -109,14 +109,14 @@ void _lock_close_recursive(_lock_t *lock) __attribute__((alias("_lock_close")));
    mutex_type is queueQUEUE_TYPE_RECURSIVE_MUTEX or queueQUEUE_TYPE_MUTEX
 */
 static int IRAM_ATTR lock_acquire_generic(_lock_t *lock, uint32_t delay, uint8_t mutex_type) {
-    xSemaphoreHandle h = (xSemaphoreHandle)(*lock);
+    SemaphoreHandle_t h = (SemaphoreHandle_t)(*lock);
     if (!h) {
         if (xTaskGetSchedulerState() == taskSCHEDULER_NOT_STARTED) {
             return 0; /* locking is a no-op before scheduler is up, so this "succeeds" */
         }
         /* lazy initialise lock - might have had a static initializer (that we don't use) */
         lock_init_generic(lock, mutex_type);
-        h = (xSemaphoreHandle)(*lock);
+        h = (SemaphoreHandle_t)(*lock);
         configASSERT(h != NULL);
     }
 
@@ -173,7 +173,7 @@ static void IRAM_ATTR lock_release_generic(_lock_t *lock, uint8_t mutex_type) {
     if (xTaskGetSchedulerState() == taskSCHEDULER_NOT_STARTED) {
         return; /* locking is a no-op before scheduler is up */
     }
-    xSemaphoreHandle h = (xSemaphoreHandle)(*lock);
+    SemaphoreHandle_t h = (SemaphoreHandle_t)(*lock);
     assert(h);
 
     if (!xPortCanYield()) {

+ 8 - 8
components/newlib/test/test_time.c

@@ -79,7 +79,7 @@ TEST_CASE("Reading RTC registers on APP CPU doesn't affect clock", "[newlib]")
         printf("(0) time taken: %f sec\n", time_sec);
         TEST_ASSERT_TRUE(fabs(time_sec - 1.0f) < 0.1);
     }
-    TEST_ASSERT_TRUE(xSemaphoreTake(done, 5000 / portTICK_RATE_MS));
+    TEST_ASSERT_TRUE(xSemaphoreTake(done, 5000 / portTICK_PERIOD_MS));
 }
 
 #endif // portNUM_PROCESSORS == 2
@@ -171,7 +171,7 @@ static volatile bool exit_flag;
 
 static void adjtimeTask2(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     struct timeval delta = {.tv_sec = 0, .tv_usec = 0};
     struct timeval outdelta;
 
@@ -188,7 +188,7 @@ static void adjtimeTask2(void *pvParameters)
 
 static void timeTask(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     struct timeval tv_time = { .tv_sec = 1520000000, .tv_usec = 900000 };
 
     // although exit flag is set in another task, checking (exit_flag == false) is safe
@@ -209,7 +209,7 @@ TEST_CASE("test for no interlocking adjtime, gettimeofday and settimeofday funct
     TEST_ASSERT_EQUAL(settimeofday(&tv_time, NULL), 0);
 
     const int max_tasks = 2;
-    xSemaphoreHandle exit_sema[max_tasks];
+    SemaphoreHandle_t exit_sema[max_tasks];
 
     for (int i = 0; i < max_tasks; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
@@ -245,7 +245,7 @@ static int64_t result_adjtime_correction_us[2];
 
 static void get_time_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     struct timeval tv_time;
     // although exit flag is set in another task, checking (exit_flag == false) is safe
     while (exit_flag == false) {
@@ -282,7 +282,7 @@ static int64_t calc_correction(const char* tag, int64_t* sys_time, int64_t* real
 
 static void measure_time_task(void *pvParameters)
 {
-    xSemaphoreHandle *sema = (xSemaphoreHandle *) pvParameters;
+    SemaphoreHandle_t *sema = (SemaphoreHandle_t *) pvParameters;
     int64_t main_real_time_us[2];
     int64_t main_sys_time_us[2];
     struct timeval tv_time = {.tv_sec = 1550000000, .tv_usec = 0};
@@ -322,7 +322,7 @@ TEST_CASE("test time adjustment happens linearly", "[newlib][timeout=15]")
 {
     exit_flag = false;
 
-    xSemaphoreHandle exit_sema[2];
+    SemaphoreHandle_t exit_sema[2];
     for (int i = 0; i < 2; ++i) {
         exit_sema[i] = xSemaphoreCreateBinary();
         result_adjtime_correction_us[i] = 0;
@@ -571,7 +571,7 @@ static void set_initial_condition(type_reboot_t type_reboot, int error_time)
 
     int delay_s = abs(error_time) * 2;
     printf("Waiting for %d (s) ...\n", delay_s);
-    vTaskDelay(delay_s * 1000 / portTICK_RATE_MS);
+    vTaskDelay(delay_s * 1000 / portTICK_PERIOD_MS);
 
     print_counters();
 

+ 7 - 15
components/protocomm/src/transports/protocomm_console.c

@@ -1,16 +1,8 @@
-// Copyright 2018 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.
-// You may obtain a copy of the License at
-//
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2018-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #include <stdio.h>
 #include <string.h>
@@ -64,7 +56,7 @@ static ssize_t hex2bin(const char *hexstr, uint8_t *bytes)
 static bool stopped(void)
 {
     uint32_t flag = 0;
-    xTaskNotifyWait(0, 0, &flag, (TickType_t) 10/portTICK_RATE_MS);
+    xTaskNotifyWait(0, 0, &flag, (TickType_t) 10/portTICK_PERIOD_MS);
     return (flag != 0);
 }
 
@@ -93,7 +85,7 @@ static void protocomm_console_task(void *arg)
         memset(linebuf, 0, sizeof(linebuf));
         i = 0;
         do {
-            ret = xQueueReceive(uart_queue, (void * )&event, (TickType_t) 10/portTICK_RATE_MS);
+            ret = xQueueReceive(uart_queue, (void * )&event, (TickType_t) 10/portTICK_PERIOD_MS);
             if (ret != pdPASS) {
                 if (stopped()) {
                     break;

+ 2 - 2
components/pthread/pthread.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2018-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2018-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -236,7 +236,7 @@ int pthread_create(pthread_t *thread, const pthread_attr_t *attr,
         if (pthread_cfg->inherit_cfg) {
             if (pthread_cfg->thread_name == NULL) {
                 // Inherit task name from current task.
-                task_name = pcTaskGetTaskName(NULL);
+                task_name = pcTaskGetName(NULL);
             } else {
                 // Inheriting, but new task name.
                 task_name = pthread_cfg->thread_name;

+ 1 - 1
components/tinyusb/additions/src/tusb_cdc_acm.c

@@ -22,7 +22,7 @@ typedef struct {
     bool initialized;
     size_t rx_unread_buf_sz;
     RingbufHandle_t rx_unread_buf;
-    xSemaphoreHandle ringbuf_read_mux;
+    SemaphoreHandle_t ringbuf_read_mux;
     uint8_t *rx_tfbuf;
     tusb_cdcacm_callback_t callback_rx;
     tusb_cdcacm_callback_t callback_rx_wanted_char;

+ 1 - 1
components/vfs/test/test_vfs_eventfd.c

@@ -296,7 +296,7 @@ TEST_CASE("eventfd select closed fd", "[vfs][eventfd]")
 }
 
 typedef struct {
-    xQueueHandle queue;
+    QueueHandle_t queue;
     int fd;
 } select_task_args_t;
 

+ 7 - 15
components/vfs/test/test_vfs_select.c

@@ -1,16 +1,8 @@
-// Copyright 2018-2019 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.
-// You may obtain a copy of the License at
-//
-//     http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
+/*
+ * SPDX-FileCopyrightText: 2018-2022 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
 
 #include <stdio.h>
 #include <unistd.h>
@@ -30,7 +22,7 @@
 typedef struct {
     int fd;
     int delay_ms;
-    xSemaphoreHandle sem;
+    SemaphoreHandle_t sem;
 } test_task_param_t;
 
 typedef struct {
@@ -40,7 +32,7 @@ typedef struct {
     int maxfds;
     struct timeval *tv;
     int select_ret;
-    xSemaphoreHandle sem;
+    SemaphoreHandle_t sem;
 } test_select_task_param_t;
 
 static const char message[] = "Hello world!";

+ 6 - 6
components/wpa_supplicant/test/test_offchannel.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2020-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  *
@@ -153,13 +153,13 @@ TEST_CASE("Test scan and ROC simultaneously", "[Offchan]")
     test_case_uses_tcpip();
     start_wifi_as_sta();
 
-    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_RATE_MS);
+    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_PERIOD_MS);
 
     TEST_ESP_OK(esp_wifi_remain_on_channel(WIFI_IF_STA, WIFI_ROC_REQ, TEST_LISTEN_CHANNEL,
                                            100, rx_cb));
     ESP_ERROR_CHECK(esp_wifi_scan_start(NULL, false));
     bits = xEventGroupWaitBits(wifi_event, WIFI_ROC_DONE_EVENT | WIFI_SCAN_DONE_EVENT,
-                               pdTRUE, pdFALSE, 5000 / portTICK_RATE_MS);
+                               pdTRUE, pdFALSE, 5000 / portTICK_PERIOD_MS);
     TEST_ASSERT_TRUE(bits == WIFI_ROC_DONE_EVENT);
 
     vTaskDelay(1000 / portTICK_PERIOD_MS);
@@ -167,7 +167,7 @@ TEST_CASE("Test scan and ROC simultaneously", "[Offchan]")
     TEST_ESP_OK(esp_wifi_remain_on_channel(WIFI_IF_STA, WIFI_ROC_REQ, TEST_LISTEN_CHANNEL,
                                            100, rx_cb));
     bits = xEventGroupWaitBits(wifi_event, WIFI_ROC_DONE_EVENT | WIFI_SCAN_DONE_EVENT,
-                               pdTRUE, pdFALSE, 5000 / portTICK_RATE_MS);
+                               pdTRUE, pdFALSE, 5000 / portTICK_PERIOD_MS);
     TEST_ASSERT_TRUE(bits == WIFI_SCAN_DONE_EVENT);
 
     stop_wifi();
@@ -181,7 +181,7 @@ static void test_wifi_offchan_tx(void)
 
     test_case_uses_tcpip();
     start_wifi_as_sta();
-    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_RATE_MS);
+    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_PERIOD_MS);
 
     unity_wait_for_signal_param("Listener mac", mac_str, 19);
 
@@ -220,7 +220,7 @@ static void test_wifi_roc(void)
     test_case_uses_tcpip();
     start_wifi_as_sta();
 
-    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_RATE_MS);
+    xEventGroupWaitBits(wifi_event, WIFI_START_EVENT, 1, 0, 5000 / portTICK_PERIOD_MS);
     TEST_ESP_OK(esp_wifi_get_mac(WIFI_IF_STA, mac));
     sprintf(mac_str, MACSTR, MAC2STR(mac));
     unity_send_signal_param("Listener mac", mac_str);

+ 2 - 2
docs/en/api-guides/SYSVIEW_FreeRTOS.txt

@@ -16,7 +16,7 @@
 135        xTaskGetTickCount
 57        xTaskGetTickCountFromISR
 136        uxTaskGetNumberOfTasks
-137        pcTaskGetTaskName                   xTaskToQuery=%t
+137        pcTaskGetName                       xTaskToQuery=%t
 138        uxTaskGetStackHighWaterMark         xTask=%t
 139        vTaskSetApplicationTaskTag          xTask=%t pxHookFunction=%u
 140        xTaskGetApplicationTaskTag          xTask=%t
@@ -52,7 +52,7 @@
 162        xTimerGetTimerDaemonTaskHandle
 163        xTimerPendFunctionCallFromISR       xFunctionToPend=%u pvParameter1=%u ulParameter2=%u pxHigherPriorityTaskWoken=%u
 164        xTimerPendFunctionCall              xFunctionToPend=%u pvParameter1=%u ulParameter2=%u xTicksToWait=%u
-165        pcTimerGetTimerName                 xTimer=%u
+165        pcTimerGetName                      xTimer=%u
 166        xTimerCreateTimerTask
 167        xTimerGenericCommand                xTimer=%u xCommandID=%u xOptionalValue=%u pxHigherPriorityTaskWoken=%u xTicksToWait=%u
 53        xQueueGenericSend                   xQueue=%I pvItemToQueue=%p xTicksToWait=%u xCopyPosition=%u

+ 1 - 1
docs/en/api-reference/protocols/modbus.rst

@@ -559,7 +559,7 @@ Example to get event when holding or input registers accessed in the slave:
     #define MB_READ_MASK            (MB_EVENT_INPUT_REG_RD | MB_EVENT_HOLDING_REG_RD)
     #define MB_WRITE_MASK           (MB_EVENT_HOLDING_REG_WR)
     #define MB_READ_WRITE_MASK      (MB_READ_MASK | MB_WRITE_MASK)
-    #define MB_PAR_INFO_GET_TOUT    (10 / portTICK_RATE_MS)                           
+    #define MB_PAR_INFO_GET_TOUT    (10 / portTICK_PERIOD_MS)                           
     ....
                                                 
     // The function blocks while waiting for register access

+ 1 - 1
docs/en/api-reference/system/freertos_additions.rst

@@ -306,7 +306,7 @@ The following example demonstrates queue set usage with ring buffers.
     ...
 
         //Block on queue set
-        xQueueSetMemberHandle member = xQueueSelectFromSet(queue_set, pdMS_TO_TICKS(1000));
+        QueueSetMemberHandle_t member = xQueueSelectFromSet(queue_set, pdMS_TO_TICKS(1000));
 
         //Check if member is ring buffer
         if (member != NULL && xRingbufferCanRead(buf_handle, member) == pdTRUE) {

+ 8 - 0
docs/en/migration-guides/freertos.rst

@@ -1,6 +1,14 @@
 Migrate FreeRTOS to ESP-IDF 5.0
 ==================================
 
+Legacy API and Data Types
+-------------------------
+
+Previously, the `configENABLE_BACKWARD_COMPATIBILITY` option was set by default, thus allowed pre FreeRTOS v8.0.0 function names and data types bo be used. The `configENABLE_BACKWARD_COMPATIBILITY` is now disabled by default, thus legacy FreeRTOS names/types are no longer supportd by default. Users should either:
+
+- Update their code to remove usage of legacy FreeRTOS names/types
+- Enable the :ref:`CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY` to explicitly allow the usage of legacy names/types
+
 Tasks Snapshot
 --------------
 

+ 2 - 2
docs/zh_CN/api-guides/SYSVIEW_FreeRTOS.txt

@@ -16,7 +16,7 @@
 135        xTaskGetTickCount
 57        xTaskGetTickCountFromISR
 136        uxTaskGetNumberOfTasks
-137        pcTaskGetTaskName                   xTaskToQuery=%t
+137        pcTaskGetName                       xTaskToQuery=%t
 138        uxTaskGetStackHighWaterMark         xTask=%t
 139        vTaskSetApplicationTaskTag          xTask=%t pxHookFunction=%u
 140        xTaskGetApplicationTaskTag          xTask=%t
@@ -52,7 +52,7 @@
 162        xTimerGetTimerDaemonTaskHandle
 163        xTimerPendFunctionCallFromISR       xFunctionToPend=%u pvParameter1=%u ulParameter2=%u pxHigherPriorityTaskWoken=%u
 164        xTimerPendFunctionCall              xFunctionToPend=%u pvParameter1=%u ulParameter2=%u xTicksToWait=%u
-165        pcTimerGetTimerName                 xTimer=%u
+165        pcTimerGetName                      xTimer=%u
 166        xTimerCreateTimerTask
 167        xTimerGenericCommand                xTimer=%u xCommandID=%u xOptionalValue=%u pxHigherPriorityTaskWoken=%u xTicksToWait=%u
 53        xQueueGenericSend                   xQueue=%I pvItemToQueue=%p xTicksToWait=%u xCopyPosition=%u

+ 4 - 4
examples/bluetooth/bluedroid/ble/ble_spp_client/main/spp_client_demo.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -104,12 +104,12 @@ static int notify_value_count = 0;
 static uint16_t count = SPP_IDX_NB;
 static esp_gattc_db_elem_t *db = NULL;
 static esp_ble_gap_cb_param_t scan_rst;
-static xQueueHandle cmd_reg_queue = NULL;
+static QueueHandle_t cmd_reg_queue = NULL;
 QueueHandle_t spp_uart_queue = NULL;
 
 #ifdef SUPPORT_HEARTBEAT
 static uint8_t  heartbeat_s[9] = {'E','s','p','r','e','s','s','i','f'};
-static xQueueHandle cmd_heartbeat_queue = NULL;
+static QueueHandle_t cmd_heartbeat_queue = NULL;
 #endif
 
 static esp_bt_uuid_t spp_service_uuid = {
@@ -551,7 +551,7 @@ void uart_task(void *pvParameters)
     uart_event_t event;
     for (;;) {
         //Waiting for UART event.
-        if (xQueueReceive(spp_uart_queue, (void * )&event, (portTickType)portMAX_DELAY)) {
+        if (xQueueReceive(spp_uart_queue, (void * )&event, (TickType_t)portMAX_DELAY)) {
             switch (event.type) {
             //Event of UART receving data
             case UART_DATA:

+ 4 - 4
examples/bluetooth/bluedroid/ble/ble_spp_server/main/ble_spp_server_demo.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -54,10 +54,10 @@ static uint16_t spp_mtu_size = 23;
 static uint16_t spp_conn_id = 0xffff;
 static esp_gatt_if_t spp_gatts_if = 0xff;
 QueueHandle_t spp_uart_queue = NULL;
-static xQueueHandle cmd_cmd_queue = NULL;
+static QueueHandle_t cmd_cmd_queue = NULL;
 
 #ifdef SUPPORT_HEARTBEAT
-static xQueueHandle cmd_heartbeat_queue = NULL;
+static QueueHandle_t cmd_heartbeat_queue = NULL;
 static uint8_t  heartbeat_s[9] = {'E','s','p','r','e','s','s','i','f'};
 static bool enable_heart_ntf = false;
 static uint8_t heartbeat_count_num = 0;
@@ -316,7 +316,7 @@ void uart_task(void *pvParameters)
 
     for (;;) {
         //Waiting for UART event.
-        if (xQueueReceive(spp_uart_queue, (void * )&event, (portTickType)portMAX_DELAY)) {
+        if (xQueueReceive(spp_uart_queue, (void * )&event, (TickType_t)portMAX_DELAY)) {
             switch (event.type) {
             //Event of UART receving data
             case UART_DATA:

+ 2 - 2
examples/bluetooth/bluedroid/classic_bt/a2dp_sink/main/bt_app_av.c

@@ -72,7 +72,7 @@ static const char *s_a2d_audio_state_str[] = {"Suspended", "Stopped", "Started"}
 static esp_avrc_rn_evt_cap_mask_t s_avrc_peer_rn_cap;
                                              /* AVRC target notification capability bit mask */
 static _lock_t s_volume_lock;
-static xTaskHandle s_vcs_task_hdl = NULL;    /* handle for volume change simulation task */
+static TaskHandle_t s_vcs_task_hdl = NULL;    /* handle for volume change simulation task */
 static uint8_t s_volume = 0;                 /* local volume value */
 static bool s_volume_notify;                 /* notify volume change or not */
 
@@ -183,7 +183,7 @@ static void volume_change_simulation(void *arg)
 
     for (;;) {
         /* volume up locally every 10 seconds */
-        vTaskDelay(10000 / portTICK_RATE_MS);
+        vTaskDelay(10000 / portTICK_PERIOD_MS);
         uint8_t volume = (s_volume + 5) & 0x7f;
         volume_set_by_local_host(volume);
     }

+ 7 - 7
examples/bluetooth/bluedroid/classic_bt/a2dp_sink/main/bt_app_core.c

@@ -34,9 +34,9 @@ static void bt_app_work_dispatched(bt_app_msg_t *msg);
  * STATIC VARIABLE DEFINITIONS
  ******************************/
 
-static xQueueHandle s_bt_app_task_queue = NULL;  /* handle of work queue */
-static xTaskHandle s_bt_app_task_handle = NULL;  /* handle of application task  */
-static xTaskHandle s_bt_i2s_task_handle = NULL;  /* handle of I2S task */
+static QueueHandle_t s_bt_app_task_queue = NULL;  /* handle of work queue */
+static TaskHandle_t s_bt_app_task_handle = NULL;  /* handle of application task  */
+static TaskHandle_t s_bt_i2s_task_handle = NULL;  /* handle of I2S task */
 static RingbufHandle_t s_ringbuf_i2s = NULL;     /* handle of ringbuffer for I2S */
 
 /*******************************
@@ -50,7 +50,7 @@ static bool bt_app_send_msg(bt_app_msg_t *msg)
     }
 
     /* send the message to work queue */
-    if (xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(BT_APP_CORE_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -70,7 +70,7 @@ static void bt_app_task_handler(void *arg)
 
     for (;;) {
         /* receive message from work queue and handle it */
-        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(BT_APP_CORE_TAG, "%s, signal: 0x%x, event: 0x%x", __func__, msg.sig, msg.event);
 
             switch (msg.sig) {
@@ -97,7 +97,7 @@ static void bt_i2s_task_handler(void *arg)
 
     for (;;) {
         /* receive data from ringbuffer and write it to I2S DMA transmit buffer */
-        data = (uint8_t *)xRingbufferReceive(s_ringbuf_i2s, &item_size, (portTickType)portMAX_DELAY);
+        data = (uint8_t *)xRingbufferReceive(s_ringbuf_i2s, &item_size, (TickType_t)portMAX_DELAY);
         if (item_size != 0){
             i2s_write(0, data, item_size, &bytes_written, portMAX_DELAY);
             vRingbufferReturnItem(s_ringbuf_i2s, (void *)data);
@@ -176,7 +176,7 @@ void bt_i2s_task_shut_down(void)
 
 size_t write_ringbuf(const uint8_t *data, size_t size)
 {
-    BaseType_t done = xRingbufferSend(s_ringbuf_i2s, (void *)data, size, (portTickType)portMAX_DELAY);
+    BaseType_t done = xRingbufferSend(s_ringbuf_i2s, (void *)data, size, (TickType_t)portMAX_DELAY);
 
     return done ? size : 0;
 }

+ 4 - 4
examples/bluetooth/bluedroid/classic_bt/a2dp_source/main/bt_app_core.c

@@ -28,8 +28,8 @@ static void bt_app_work_dispatched(bt_app_msg_t *msg);
 /*********************************
  * STATIC VARIABLE DEFINITIONS
  ********************************/
-static xQueueHandle s_bt_app_task_queue = NULL;
-static xTaskHandle s_bt_app_task_handle = NULL;
+static QueueHandle_t s_bt_app_task_queue = NULL;
+static TaskHandle_t s_bt_app_task_handle = NULL;
 
 /*********************************
  * STATIC FUNCTION DEFINITIONS
@@ -41,7 +41,7 @@ static bool bt_app_send_msg(bt_app_msg_t *msg)
         return false;
     }
 
-    if (pdTRUE != xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_RATE_MS)) {
+    if (pdTRUE != xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_PERIOD_MS)) {
         ESP_LOGE(BT_APP_CORE_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -62,7 +62,7 @@ static void bt_app_task_handler(void *arg)
 
     for (;;) {
         /* receive message from work queue and handle it */
-        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(BT_APP_CORE_TAG, "%s, signal: 0x%x, event: 0x%x", __func__, msg.sig, msg.event);
 
             switch (msg.sig) {

+ 1 - 1
examples/bluetooth/bluedroid/classic_bt/a2dp_source/main/main.c

@@ -325,7 +325,7 @@ static void bt_av_hdl_stack_evt(uint16_t event, void *p_param)
         /* create and start heart beat timer */
         do {
             int tmr_id = 0;
-            s_tmr = xTimerCreate("connTmr", (10000 / portTICK_RATE_MS),
+            s_tmr = xTimerCreate("connTmr", (10000 / portTICK_PERIOD_MS),
                                  pdTRUE, (void *) &tmr_id, bt_app_a2d_heart_beat);
             xTimerStart(s_tmr, portMAX_DELAY);
         } while (0);

+ 2 - 2
examples/bluetooth/bluedroid/classic_bt/bt_hid_mouse_device/main/main.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -26,7 +26,7 @@ typedef struct
     esp_hidd_qos_param_t both_qos;
     uint8_t protocol_mode;
     SemaphoreHandle_t mouse_mutex;
-    xTaskHandle mouse_task_hdl;
+    TaskHandle_t mouse_task_hdl;
     uint8_t buffer[4];
     int8_t x_dir;
 } local_param_t;

+ 2 - 2
examples/bluetooth/bluedroid/classic_bt/bt_spp_initiator/main/console_uart.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -48,7 +48,7 @@ static void console_uart_task(void *pvParameters)
 
     for (;;) {
         //Waiting for UART event.
-        if (xQueueReceive(uart_queue, (void * )&event, (portTickType)portMAX_DELAY)) {
+        if (xQueueReceive(uart_queue, (void * )&event, (TickType_t)portMAX_DELAY)) {
             switch (event.type) {
                 //Event of UART receving data
                 case UART_DATA:

+ 5 - 5
examples/bluetooth/bluedroid/classic_bt/bt_spp_vfs_acceptor/main/spp_task.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -19,8 +19,8 @@ static void spp_task_task_handler(void *arg);
 static bool spp_task_send_msg(spp_task_msg_t *msg);
 static void spp_task_work_dispatched(spp_task_msg_t *msg);
 
-static xQueueHandle spp_task_task_queue = NULL;
-static xTaskHandle spp_task_task_handle = NULL;
+static QueueHandle_t spp_task_task_queue = NULL;
+static TaskHandle_t spp_task_task_handle = NULL;
 
 bool spp_task_work_dispatch(spp_task_cb_t p_cback, uint16_t event, void *p_params, int param_len, spp_task_copy_cb_t p_copy_cback)
 {
@@ -55,7 +55,7 @@ static bool spp_task_send_msg(spp_task_msg_t *msg)
         return false;
     }
 
-    if (xQueueSend(spp_task_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(spp_task_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(SPP_TASK_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -73,7 +73,7 @@ static void spp_task_task_handler(void *arg)
 {
     spp_task_msg_t msg;
     for (;;) {
-        if (pdTRUE == xQueueReceive(spp_task_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(spp_task_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(SPP_TASK_TAG, "%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
             switch (msg.sig) {
             case SPP_TASK_SIG_WORK_DISPATCH:

+ 5 - 5
examples/bluetooth/bluedroid/classic_bt/bt_spp_vfs_initiator/main/spp_task.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -19,8 +19,8 @@ static void spp_task_task_handler(void *arg);
 static bool spp_task_send_msg(spp_task_msg_t *msg);
 static void spp_task_work_dispatched(spp_task_msg_t *msg);
 
-static xQueueHandle spp_task_task_queue = NULL;
-static xTaskHandle spp_task_task_handle = NULL;
+static QueueHandle_t spp_task_task_queue = NULL;
+static TaskHandle_t spp_task_task_handle = NULL;
 
 bool spp_task_work_dispatch(spp_task_cb_t p_cback, uint16_t event, void *p_params, int param_len, spp_task_copy_cb_t p_copy_cback)
 {
@@ -55,7 +55,7 @@ static bool spp_task_send_msg(spp_task_msg_t *msg)
         return false;
     }
 
-    if (xQueueSend(spp_task_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(spp_task_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(SPP_TASK_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -73,7 +73,7 @@ static void spp_task_task_handler(void *arg)
 {
     spp_task_msg_t msg;
     for (;;) {
-        if (pdTRUE == xQueueReceive(spp_task_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(spp_task_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(SPP_TASK_TAG, "%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
             switch (msg.sig) {
             case SPP_TASK_SIG_WORK_DISPATCH:

+ 5 - 5
examples/bluetooth/bluedroid/classic_bt/hfp_ag/main/bt_app_core.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -19,8 +19,8 @@ static void bt_app_task_handler(void *arg);
 static bool bt_app_send_msg(bt_app_msg_t *msg);
 static void bt_app_work_dispatched(bt_app_msg_t *msg);
 
-static xQueueHandle bt_app_task_queue = NULL;
-static xTaskHandle bt_app_task_handle = NULL;
+static QueueHandle_t bt_app_task_queue = NULL;
+static TaskHandle_t bt_app_task_handle = NULL;
 
 bool bt_app_work_dispatch(bt_app_cb_t p_cback, uint16_t event, void *p_params, int param_len, bt_app_copy_cb_t p_copy_cback)
 {
@@ -54,7 +54,7 @@ static bool bt_app_send_msg(bt_app_msg_t *msg)
         return false;
     }
 
-    if (xQueueSend(bt_app_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(bt_app_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(BT_APP_CORE_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -72,7 +72,7 @@ static void bt_app_task_handler(void *arg)
 {
     bt_app_msg_t msg;
     for (;;) {
-        if (pdTRUE == xQueueReceive(bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(bt_app_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(BT_APP_CORE_TAG, "%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
             switch (msg.sig) {
             case BT_APP_SIG_WORK_DISPATCH:

+ 4 - 4
examples/bluetooth/bluedroid/classic_bt/hfp_ag/main/bt_app_hf.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -141,8 +141,8 @@ static uint64_t s_time_new, s_time_old;
 static esp_timer_handle_t s_periodic_timer;
 static uint64_t s_last_enter_time, s_now_enter_time;
 static uint64_t s_us_duration;
-static xSemaphoreHandle s_send_data_Semaphore = NULL;
-static xTaskHandle s_bt_app_send_data_task_handler = NULL;
+static SemaphoreHandle_t s_send_data_Semaphore = NULL;
+static TaskHandle_t s_bt_app_send_data_task_handler = NULL;
 static esp_hf_audio_state_t s_audio_code;
 
 static void print_speed(void);
@@ -214,7 +214,7 @@ static void bt_app_send_data_task(void *arg)
     uint32_t item_size = 0;
     uint8_t *buf = NULL;
     for (;;) {
-        if (xSemaphoreTake(s_send_data_Semaphore, (portTickType)portMAX_DELAY)) {
+        if (xSemaphoreTake(s_send_data_Semaphore, (TickType_t)portMAX_DELAY)) {
             s_now_enter_time = esp_timer_get_time();
             s_us_duration = s_now_enter_time - s_last_enter_time;
             if(s_audio_code == ESP_HF_AUDIO_STATE_CONNECTED_MSBC) {

+ 5 - 5
examples/bluetooth/bluedroid/classic_bt/hfp_hf/main/bt_app_core.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -19,8 +19,8 @@ static void bt_app_task_handler(void *arg);
 static bool bt_app_send_msg(bt_app_msg_t *msg);
 static void bt_app_work_dispatched(bt_app_msg_t *msg);
 
-static xQueueHandle bt_app_task_queue = NULL;
-static xTaskHandle bt_app_task_handle = NULL;
+static QueueHandle_t bt_app_task_queue = NULL;
+static TaskHandle_t bt_app_task_handle = NULL;
 
 bool bt_app_work_dispatch(bt_app_cb_t p_cback, uint16_t event, void *p_params, int param_len, bt_app_copy_cb_t p_copy_cback)
 {
@@ -55,7 +55,7 @@ static bool bt_app_send_msg(bt_app_msg_t *msg)
         return false;
     }
 
-    if (xQueueSend(bt_app_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(bt_app_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(BT_APP_CORE_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -73,7 +73,7 @@ static void bt_app_task_handler(void *arg)
 {
     bt_app_msg_t msg;
     for (;;) {
-        if (pdTRUE == xQueueReceive(bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(bt_app_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(BT_APP_CORE_TAG, "%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
             switch (msg.sig) {
                 case BT_APP_SIG_WORK_DISPATCH:

+ 3 - 3
examples/bluetooth/bluedroid/coex/a2dp_gatts_coex/main/bt_app_av.c

@@ -1,6 +1,6 @@
 
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -45,7 +45,7 @@ static const char *s_a2d_conn_state_str[] = {"Disconnected", "Connecting", "Conn
 static const char *s_a2d_audio_state_str[] = {"Suspended", "Stopped", "Started"};
 static esp_avrc_rn_evt_cap_mask_t s_avrc_peer_rn_cap;
 static _lock_t s_volume_lock;
-static xTaskHandle s_vcs_task_hdl = NULL;
+static TaskHandle_t s_vcs_task_hdl = NULL;
 static uint8_t s_volume = 0;
 static bool s_volume_notify;
 
@@ -314,7 +314,7 @@ static void volume_change_simulation(void *arg)
     ESP_LOGI(BT_RC_TG_TAG, "start volume change simulation");
 
     for (;;) {
-        vTaskDelay(10000 / portTICK_RATE_MS);
+        vTaskDelay(10000 / portTICK_PERIOD_MS);
 
         uint8_t volume = (s_volume + 5) & 0x7f;
         volume_set_by_local_host(volume);

+ 8 - 8
examples/bluetooth/bluedroid/coex/a2dp_gatts_coex/main/bt_app_core.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -21,9 +21,9 @@ static void bt_app_task_handler(void *arg);
 static bool bt_app_send_msg(bt_app_msg_t *msg);
 static void bt_app_work_dispatched(bt_app_msg_t *msg);
 
-static xQueueHandle s_bt_app_task_queue = NULL;
-static xTaskHandle s_bt_app_task_handle = NULL;
-static xTaskHandle s_bt_i2s_task_handle = NULL;
+static QueueHandle_t s_bt_app_task_queue = NULL;
+static TaskHandle_t s_bt_app_task_handle = NULL;
+static TaskHandle_t s_bt_i2s_task_handle = NULL;
 static RingbufHandle_t s_ringbuf_i2s = NULL;;
 
 bool bt_app_work_dispatch(bt_app_cb_t p_cback, uint16_t event, void *p_params, int param_len, bt_app_copy_cb_t p_copy_cback)
@@ -59,7 +59,7 @@ static bool bt_app_send_msg(bt_app_msg_t *msg)
         return false;
     }
 
-    if (xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_RATE_MS) != pdTRUE) {
+    if (xQueueSend(s_bt_app_task_queue, msg, 10 / portTICK_PERIOD_MS) != pdTRUE) {
         ESP_LOGE(BT_APP_CORE_TAG, "%s xQueue send failed", __func__);
         return false;
     }
@@ -77,7 +77,7 @@ static void bt_app_task_handler(void *arg)
 {
     bt_app_msg_t msg;
     for (;;) {
-        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(s_bt_app_task_queue, &msg, (TickType_t)portMAX_DELAY)) {
             ESP_LOGD(BT_APP_CORE_TAG, "%s, sig 0x%x, 0x%x", __func__, msg.sig, msg.event);
             switch (msg.sig) {
             case BT_APP_SIG_WORK_DISPATCH:
@@ -121,7 +121,7 @@ static void bt_i2s_task_handler(void *arg)
     size_t bytes_written = 0;
 
     for (;;) {
-        data = (uint8_t *)xRingbufferReceive(s_ringbuf_i2s, &item_size, (portTickType)portMAX_DELAY);
+        data = (uint8_t *)xRingbufferReceive(s_ringbuf_i2s, &item_size, (TickType_t)portMAX_DELAY);
         if (item_size != 0){
             i2s_write(0, data, item_size, &bytes_written, portMAX_DELAY);
             vRingbufferReturnItem(s_ringbuf_i2s,(void *)data);
@@ -155,7 +155,7 @@ void bt_i2s_task_shut_down(void)
 
 size_t write_ringbuf(const uint8_t *data, size_t size)
 {
-    BaseType_t done = xRingbufferSend(s_ringbuf_i2s, (void *)data, size, (portTickType)portMAX_DELAY);
+    BaseType_t done = xRingbufferSend(s_ringbuf_i2s, (void *)data, size, (TickType_t)portMAX_DELAY);
     if(done){
         return size;
     } else {

+ 4 - 4
examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/run_tc.c

@@ -1,7 +1,7 @@
 /*
  * ESP BLE Mesh Example
  *
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -15,7 +15,7 @@
 
 #define TAG "CASE"
 
-xQueueHandle xTaskQueue = 0;
+QueueHandle_t xTaskQueue = 0;
 
 static const char *coex_get_case_env(coex_test_env_t *test_env, const char *keyword)
 {
@@ -248,7 +248,7 @@ static void excute_case(void *arg)
     }
 
     if (run_case && run_case->func_stop != NULL ) {
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
         run_case->func_stop();
     }
     vTaskDelete(NULL);
@@ -260,7 +260,7 @@ static void run_task(void *arg)
     run_task_msg_t msg;
 
     for (;;) {
-        if (pdTRUE == xQueueReceive(xTaskQueue, &msg, (portTickType)portMAX_DELAY)) {
+        if (pdTRUE == xQueueReceive(xTaskQueue, &msg, (TickType_t)portMAX_DELAY)) {
             if ( msg.case_id < sizeof(tc_case) / sizeof(tc_case[0]) ) {
                 xTaskCreatePinnedToCore(excute_case, tc_case_table->name, 4096, &tc_case_table[msg.case_id], RUN_TASK_PRIORITY, NULL, 0);
             } else {

+ 2 - 2
examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/run_tc.h

@@ -1,7 +1,7 @@
 /*
  * ESP BLE Mesh Example
  *
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -48,7 +48,7 @@ typedef struct run_task_msg {
     uint8_t case_id;
 } run_task_msg_t;
 
-extern xQueueHandle xTaskQueue ;
+extern QueueHandle_t xTaskQueue ;
 
 void run_tc_init(void);
 

+ 2 - 2
examples/bluetooth/esp_ble_mesh/ble_mesh_coex_test/components/case/sync.c

@@ -1,7 +1,7 @@
 /*
  * ESP BLE Mesh Example
  *
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -422,7 +422,7 @@ static void handle_sync_timeout(void *arg)
 {
     static bool run_first = true;
     if (run_first == true) {
-        xSemaphoreTake((SemaphoreHandle_t)arg, (portTickType)portMAX_DELAY);
+        xSemaphoreTake((SemaphoreHandle_t)arg, (TickType_t)portMAX_DELAY);
         esp_timer_start_periodic( (esp_timer_handle_t)arg, 1000000);
         run_first = false;
     }

+ 1 - 1
examples/bluetooth/esp_ble_mesh/ble_mesh_console/main/ble_mesh_adapter.h

@@ -65,7 +65,7 @@ extern ble_mesh_node_statistics_t ble_mesh_node_statistics;
 
 extern SemaphoreHandle_t ble_mesh_node_sema;
 
-#define SEND_MESSAGE_TIMEOUT (30000/portTICK_RATE_MS)
+#define SEND_MESSAGE_TIMEOUT (30000/portTICK_PERIOD_MS)
 
 #define arg_int_to_value(src_msg, dst_msg, message) do { \
     if (src_msg->count != 0) {\

+ 2 - 2
examples/bluetooth/esp_ble_mesh/ble_mesh_console/main/transaction.c

@@ -1,5 +1,5 @@
 /*
- * SPDX-FileCopyrightText: 2017-2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2017-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -193,7 +193,7 @@ esp_err_t transaction_run(transaction_t *trans)
 
             // trans->event_group and trans->wait_events will not be changed once trans is created, so we don't need protect them
             current_bits = xEventGroupWaitBits(trans->event_group, trans->wait_events | TRANSACTION_ABORT_EVENT,
-                    1, 0, wait_time/portTICK_RATE_MS);
+                    1, 0, wait_time/portTICK_PERIOD_MS);
 
             xSemaphoreTakeRecursive(trans_mutex, portMAX_DELAY);
             trans->current_bits |= current_bits;

+ 1 - 1
examples/bluetooth/esp_ble_mesh/ble_mesh_node/onoff_client/tutorial/BLE_Mesh_Node_OnOff_Client_Example_Walkthrough.md

@@ -205,7 +205,7 @@ static void board_uart_task(void *p)
     uint32_t input;
     
     while (1) { 
-        int len = uart_read_bytes(MESH_UART_NUM, data, UART_BUF_SIZE, 100 / portTICK_RATE_MS);
+        int len = uart_read_bytes(MESH_UART_NUM, data, UART_BUF_SIZE, 100 / portTICK_PERIOD_MS);
         if (len > 0) {
             input = strtoul((const char *)data, NULL, 16);
             remote_addr = input & 0xFFFF;

+ 3 - 3
examples/bluetooth/esp_ble_mesh/ble_mesh_wifi_coexist/main/cmd_wifi.c

@@ -1,7 +1,7 @@
 /*
  * Iperf example - wifi commands
  *
- * SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
+ * SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
  *
  * SPDX-License-Identifier: Unlicense OR CC0-1.0
  */
@@ -161,7 +161,7 @@ static bool wifi_cmd_sta_join(const char *ssid, const char *pass)
         reconnect = false;
         xEventGroupClearBits(wifi_event_group, CONNECTED_BIT);
         ESP_ERROR_CHECK( esp_wifi_disconnect() );
-        xEventGroupWaitBits(wifi_event_group, DISCONNECTED_BIT, 0, 1, portTICK_RATE_MS);
+        xEventGroupWaitBits(wifi_event_group, DISCONNECTED_BIT, 0, 1, portTICK_PERIOD_MS);
     }
 
     reconnect = true;
@@ -170,7 +170,7 @@ static bool wifi_cmd_sta_join(const char *ssid, const char *pass)
     ESP_ERROR_CHECK( esp_wifi_set_config(WIFI_IF_STA, &wifi_config) );
     esp_wifi_connect();
 
-    xEventGroupWaitBits(wifi_event_group, CONNECTED_BIT, 0, 1, 5000 / portTICK_RATE_MS);
+    xEventGroupWaitBits(wifi_event_group, CONNECTED_BIT, 0, 1, 5000 / portTICK_PERIOD_MS);
 
     return true;
 }

برخی فایل ها در این مقایسه diff نمایش داده نمی شوند زیرا تعداد فایل ها بسیار زیاد است