From a5cc728079bb4bb9d0f31891117f129bb8abdeb3 Mon Sep 17 00:00:00 2001
From: Our Air Quality <info@ourairquality.org>
Date: Sat, 5 Nov 2016 21:04:03 +1100
Subject: [PATCH] FreeRTOS type updates. (#261)

---
 FreeRTOS/Source/include/FreeRTOSConfig.h      |  6 ++++-
 FreeRTOS/Source/portable/esp8266/port.c       |  4 ++--
 FreeRTOS/Source/portable/esp8266/portmacro.h  |  5 ++---
 core/app_main.c                               |  6 ++---
 core/sysparam.c                               |  2 +-
 examples/access_point/access_point.c          |  2 +-
 examples/aws_iot/aws_iot.c                    | 16 +++++++-------
 examples/aws_iot/ssl_connection.c             |  2 +-
 examples/blink/blink.c                        |  8 +++----
 examples/bmp180_i2c/bmp180_i2c.c              | 12 +++++-----
 examples/bmp280/bmp280_example.c              |  8 +++----
 examples/button/button.c                      | 10 ++++-----
 examples/dht_sensor/dht_sensor.c              |  2 +-
 .../ds18b20_broadcaster/ds18b20_broadcaster.c |  4 ++--
 examples/ds18b20_onewire/ds18b20_onewire.c    |  2 +-
 examples/experiments/timers/timers.c          |  2 +-
 .../unaligned_load/unaligned_load.c           |  4 ++--
 examples/fatfs_rtc/main.c                     |  2 +-
 examples/http_get/http_get.c                  | 10 ++++-----
 examples/http_get_mbedtls/http_get_mbedtls.c  |  4 ++--
 examples/i2s_audio/i2s_audio_example.c        |  4 ++--
 examples/mqtt_client/mqtt_client.c            | 12 +++++-----
 examples/ota_basic/ota_basic.c                |  4 ++--
 examples/posix_fs/posix_fs_example.c          |  4 ++--
 examples/simple/simple.c                      |  6 ++---
 examples/sntp/sntp_example.c                  |  2 +-
 examples/spiffs/spiffs_example.c              |  2 +-
 examples/ssd1306_i2c/ssd1306_i2c.c            | 10 ++++-----
 examples/terminal/terminal.c                  |  2 +-
 examples/tsl2561/tsl2561_example.c            |  2 +-
 examples/ws2812_i2s/ws2812_i2s_colour_loop.c  |  2 +-
 examples/ws2812_rainbow/ws2812_rainbow.c      |  2 +-
 extras/bmp180/README.md                       |  2 +-
 extras/bmp180/bmp180.c                        | 20 ++++++++---------
 extras/bmp180/bmp180.h                        |  8 +++----
 extras/bmp280/README.md                       |  4 ++--
 extras/cpp_support/include/countdown.hpp      |  4 ++--
 extras/cpp_support/include/mutex.hpp          |  4 ++--
 extras/cpp_support/include/queue.hpp          |  6 ++---
 extras/cpp_support/include/task.hpp           |  4 ++--
 extras/dhcpserver/dhcpserver.c                |  2 +-
 extras/ds18b20/ds18b20.c                      |  6 ++---
 extras/fatfs/ffconf.h                         |  2 +-
 extras/fatfs/syscall.c                        |  8 +++----
 extras/paho_mqtt_c/MQTTESP8266.c              | 14 ++++++------
 extras/paho_mqtt_c/MQTTESP8266.h              |  2 +-
 .../stdin_uart_interrupt.c                    |  2 +-
 extras/tsl2561/tsl2561.c                      |  6 ++---
 include/etstimer.h                            |  2 +-
 lwip/include/arch/sys_arch.h                  | 12 +++++-----
 lwip/sys_arch.c                               | 22 +++++++++----------
 open_esplibs/libmain/os_cpu_a.c               |  4 ++--
 open_esplibs/libmain/timers.c                 |  2 +-
 53 files changed, 151 insertions(+), 148 deletions(-)

diff --git a/FreeRTOS/Source/include/FreeRTOSConfig.h b/FreeRTOS/Source/include/FreeRTOSConfig.h
index fc3b283..7df92bf 100644
--- a/FreeRTOS/Source/include/FreeRTOSConfig.h
+++ b/FreeRTOS/Source/include/FreeRTOSConfig.h
@@ -44,7 +44,7 @@
 #define configCPU_CLOCK_HZ			( ( unsigned long ) 80000000 )
 #endif
 #ifndef configTICK_RATE_HZ
-#define configTICK_RATE_HZ			( ( portTickType ) 100 )
+#define configTICK_RATE_HZ			( ( TickType_t ) 100 )
 #endif
 #ifndef configMAX_PRIORITIES
 #define configMAX_PRIORITIES		( ( unsigned portBASE_TYPE ) 15 )
@@ -140,5 +140,9 @@ to exclude the API function. */
 #define INCLUDE_uxTaskGetStackHighWaterMark 1
 #endif
 
+#ifndef configENABLE_BACKWARD_COMPATIBILITY
+#define configENABLE_BACKWARD_COMPATIBILITY 0
+#endif
+
 #endif /* __DEFAULT_FREERTOS_CONFIG_H */
 
diff --git a/FreeRTOS/Source/portable/esp8266/port.c b/FreeRTOS/Source/portable/esp8266/port.c
index b5d272f..87d846f 100644
--- a/FreeRTOS/Source/portable/esp8266/port.c
+++ b/FreeRTOS/Source/portable/esp8266/port.c
@@ -94,7 +94,7 @@ void *xPortSupervisorStackPointer;
 /*
  * Stack initialization
  */
-portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters )
+portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
 {
     #define SET_STKREG(r,v) sp[(r) >> 2] = (portSTACK_TYPE)(v)
     portSTACK_TYPE *sp, *tp;
@@ -259,7 +259,7 @@ void IRAM vPortExitCritical( void )
 }
 
 /* Backward compatibility with libmain.a and libpp.a and can remove when these are open. */
-signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions )
+signed portBASE_TYPE xTaskGenericCreate( TaskFunction_t pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, TaskHandle_t *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const MemoryRegion_t * const xRegions )
 {
     (void)puxStackBuffer; (void)xRegions;
     return xTaskCreate( pxTaskCode, (const char * const)pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask);
diff --git a/FreeRTOS/Source/portable/esp8266/portmacro.h b/FreeRTOS/Source/portable/esp8266/portmacro.h
index 645f5c4..19c9248 100644
--- a/FreeRTOS/Source/portable/esp8266/portmacro.h
+++ b/FreeRTOS/Source/portable/esp8266/portmacro.h
@@ -100,13 +100,12 @@ typedef portSTACK_TYPE StackType_t;
 typedef portBASE_TYPE BaseType_t;
 typedef unsigned portBASE_TYPE UBaseType_t;
 
-typedef uint32_t portTickType;
 typedef uint32_t TickType_t;
-#define portMAX_DELAY ( portTickType ) 0xffffffff
+#define portMAX_DELAY ( TickType_t ) 0xffffffff
 
 /* Architecture specifics. */
 #define portSTACK_GROWTH			( -1 )
-#define portTICK_PERIOD_MS			( ( portTickType ) 1000 / configTICK_RATE_HZ )
+#define portTICK_PERIOD_MS			( ( TickType_t ) 1000 / configTICK_RATE_HZ )
 #define portBYTE_ALIGNMENT			8
 /*-----------------------------------------------------------*/
 
diff --git a/core/app_main.c b/core/app_main.c
index 6662301..63142cd 100644
--- a/core/app_main.c
+++ b/core/app_main.c
@@ -52,10 +52,10 @@ uint8_t sdk_user_init_flag;
 struct sdk_info_st sdk_info;
 
 // xUserTaskHandle -- .bss+0x28
-xTaskHandle sdk_xUserTaskHandle;
+TaskHandle_t sdk_xUserTaskHandle;
 
 // xWatchDogTaskHandle -- .bss+0x2c
-xTaskHandle sdk_xWatchDogTaskHandle;
+TaskHandle_t sdk_xWatchDogTaskHandle;
 
 /* Static function prototypes */
 
@@ -227,7 +227,7 @@ void IRAM sdk_user_start(void) {
 }
 
 // .text+0x3a8
-void IRAM vApplicationStackOverflowHook(xTaskHandle task, char *task_name) {
+void IRAM vApplicationStackOverflowHook(TaskHandle_t task, char *task_name) {
     printf("Task stack overflow (high water mark=%lu name=\"%s\")\n", uxTaskGetStackHighWaterMark(task), task_name);
 }
 
diff --git a/core/sysparam.c b/core/sysparam.c
index 290ddb3..f00f161 100644
--- a/core/sysparam.c
+++ b/core/sysparam.c
@@ -114,7 +114,7 @@ static struct {
     uint32_t end_addr;
     size_t region_size;
     bool force_compact;
-    xSemaphoreHandle sem;
+    SemaphoreHandle_t sem;
 } _sysparam_info;
 
 /***************************** Internal routines *****************************/
diff --git a/examples/access_point/access_point.c b/examples/access_point/access_point.c
index 05e344a..f8fcd50 100644
--- a/examples/access_point/access_point.c
+++ b/examples/access_point/access_point.c
@@ -84,7 +84,7 @@ static void telnetTask(void *pvParameters)
 
     char buf[80];
     snprintf(buf, sizeof(buf), "Uptime %d seconds\r\n",
-	     xTaskGetTickCount()*portTICK_RATE_MS/1000);
+	     xTaskGetTickCount()*portTICK_PERIOD_MS/1000);
     netconn_write(client, buf, strlen(buf), NETCONN_COPY);
     snprintf(buf, sizeof(buf), "Free heap %d bytes\r\n", (int)xPortGetFreeHeapSize());
     netconn_write(client, buf, strlen(buf), NETCONN_COPY);
diff --git a/examples/aws_iot/aws_iot.c b/examples/aws_iot/aws_iot.c
index 8b26b99..08ce9f4 100644
--- a/examples/aws_iot/aws_iot.c
+++ b/examples/aws_iot/aws_iot.c
@@ -31,7 +31,7 @@ extern char *ca_cert, *client_endpoint, *client_cert, *client_key;
 static int wifi_alive = 0;
 static int ssl_reset;
 static SSLConnection *ssl_conn;
-static xQueueHandle publish_queue;
+static QueueHandle_t publish_queue;
 
 static void beat_task(void *pvParameters) {
     char msg[16];
@@ -39,7 +39,7 @@ static void beat_task(void *pvParameters) {
 
     while (1) {
         if (!wifi_alive) {
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             continue;
         }
 
@@ -50,7 +50,7 @@ static void beat_task(void *pvParameters) {
             printf("Publish queue overflow\r\n");
         }
 
-        vTaskDelay(10000 / portTICK_RATE_MS);
+        vTaskDelay(10000 / portTICK_PERIOD_MS);
     }
 }
 
@@ -142,7 +142,7 @@ static void mqtt_task(void *pvParameters) {
     ssl_conn = (SSLConnection *) malloc(sizeof(SSLConnection));
     while (1) {
         if (!wifi_alive) {
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             continue;
         }
 
@@ -191,7 +191,7 @@ static void mqtt_task(void *pvParameters) {
         while (wifi_alive && !ssl_reset) {
             char msg[64];
             while (xQueueReceive(publish_queue, (void *) msg, 0) == pdTRUE) {
-                portTickType task_tick = xTaskGetTickCount();
+                TickType_t task_tick = xTaskGetTickCount();
                 uint32_t free_heap = xPortGetFreeHeapSize();
                 uint32_t free_stack = uxTaskGetStackHighWaterMark(NULL);
                 snprintf(msg, sizeof(msg), "%u: free heap %u, free stack %u",
@@ -246,7 +246,7 @@ static void wifi_task(void *pvParameters) {
                 printf("WiFi: connection failed\r\n");
                 break;
             }
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             --retries;
         }
 
@@ -256,12 +256,12 @@ static void wifi_task(void *pvParameters) {
                 printf("WiFi: Connected\n\r");
                 wifi_alive = 1;
             }
-            vTaskDelay(500 / portTICK_RATE_MS);
+            vTaskDelay(500 / portTICK_PERIOD_MS);
         }
 
         wifi_alive = 0;
         printf("WiFi: disconnected\n\r");
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/aws_iot/ssl_connection.c b/examples/aws_iot/ssl_connection.c
index be5bb23..24dafb0 100644
--- a/examples/aws_iot/ssl_connection.c
+++ b/examples/aws_iot/ssl_connection.c
@@ -133,7 +133,7 @@ int ssl_connect(SSLConnection* conn, const char* host, int port) {
         }
         handle_error(ret);
 
-        vTaskDelay(5000 / portTICK_RATE_MS);
+        vTaskDelay(5000 / portTICK_PERIOD_MS);
     }
 
     mbedtls_ssl_get_record_expansion(&conn->ssl_ctx);
diff --git a/examples/blink/blink.c b/examples/blink/blink.c
index 341ac08..9de0f20 100644
--- a/examples/blink/blink.c
+++ b/examples/blink/blink.c
@@ -19,9 +19,9 @@ void blinkenTask(void *pvParameters)
     gpio_enable(gpio, GPIO_OUTPUT);
     while(1) {
         gpio_write(gpio, 1);
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         gpio_write(gpio, 0);
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
     }
 }
 
@@ -45,9 +45,9 @@ void blinkenRegisterTask(void *pvParameters)
     IOMUX_GPIO2 = IOMUX_GPIO2_FUNC_GPIO | IOMUX_PIN_OUTPUT_ENABLE; /* change this line if you change 'gpio' */
     while(1) {
         GPIO.OUT_SET = BIT(gpio);
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
         GPIO.OUT_CLEAR = BIT(gpio);
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/bmp180_i2c/bmp180_i2c.c b/examples/bmp180_i2c/bmp180_i2c.c
index d05aca8..1e188bc 100644
--- a/examples/bmp180_i2c/bmp180_i2c.c
+++ b/examples/bmp180_i2c/bmp180_i2c.c
@@ -26,11 +26,11 @@ typedef struct
 } my_event_t;
 
 // Communication Queue
-static xQueueHandle mainqueue;
-static xTimerHandle timerHandle;
+static QueueHandle_t mainqueue;
+static TimerHandle_t timerHandle;
 
 // Own BMP180 User Inform Implementation
-bool bmp180_i2c_informUser(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure)
+bool bmp180_i2c_informUser(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure)
 {
     my_event_t ev;
 
@@ -43,7 +43,7 @@ bool bmp180_i2c_informUser(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_
 }
 
 // Timer call back
-static void bmp180_i2c_timer_cb(xTimerHandle xTimer)
+static void bmp180_i2c_timer_cb(TimerHandle_t xTimer)
 {
     my_event_t ev;
     ev.event_type = MY_EVT_TIMER;
@@ -55,7 +55,7 @@ static void bmp180_i2c_timer_cb(xTimerHandle xTimer)
 void bmp180_task(void *pvParameters)
 {
     // Received pvParameters is communication queue
-    xQueueHandle *com_queue = (xQueueHandle *)pvParameters;
+    QueueHandle_t *com_queue = (QueueHandle_t *)pvParameters;
 
     printf("%s: Started user interface task\n", __FUNCTION__);
 
@@ -116,7 +116,7 @@ void user_init(void)
     xTaskCreate(bmp180_task, "bmp180_task", 256, &mainqueue, 2, NULL);
 
     // Create Timer (Trigger a measurement every second)
-    timerHandle = xTimerCreate("BMP180 Trigger", 1000/portTICK_RATE_MS, pdTRUE, NULL, bmp180_i2c_timer_cb);
+    timerHandle = xTimerCreate("BMP180 Trigger", 1000/portTICK_PERIOD_MS, pdTRUE, NULL, bmp180_i2c_timer_cb);
 
     if (timerHandle != NULL)
     {
diff --git a/examples/bmp280/bmp280_example.c b/examples/bmp280/bmp280_example.c
index e80d6b0..c4c7c11 100644
--- a/examples/bmp280/bmp280_example.c
+++ b/examples/bmp280/bmp280_example.c
@@ -31,14 +31,14 @@ static void bmp280_task_forced(void *pvParameters)
     while (1) {
         while (!bmp280_init(&bmp280_dev, &params)) {
             printf("BMP280 initialization failed\n");
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
         }
 
         bool bme280p = bmp280_dev.id == BME280_CHIP_ID;
         printf("BMP280: found %s\n", bme280p ? "BME280" : "BMP280");
 
         while(1) {
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             if (!bmp280_force_measurement(&bmp280_dev)) {
                 printf("Failed initiating measurement\n");
                 break;
@@ -72,14 +72,14 @@ static void bmp280_task_normal(void *pvParameters)
     while (1) {
         while (!bmp280_init(&bmp280_dev, &params)) {
             printf("BMP280 initialization failed\n");
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
         }
 
         bool bme280p = bmp280_dev.id == BME280_CHIP_ID;
         printf("BMP280: found %s\n", bme280p ? "BME280" : "BMP280");
 
         while(1) {
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             if (!bmp280_read_float(&bmp280_dev, &temperature, &pressure, &humidity)) {
                 printf("Temperature/pressure reading failed\n");
                 break;
diff --git a/examples/button/button.c b/examples/button/button.c
index 7bebf81..a371f0d 100644
--- a/examples/button/button.c
+++ b/examples/button/button.c
@@ -34,8 +34,8 @@ void buttonPollTask(void *pvParameters)
         {
             taskYIELD();
         }
-        printf("Polled for button press at %dms\r\n", xTaskGetTickCount()*portTICK_RATE_MS);
-        vTaskDelay(200 / portTICK_RATE_MS);
+        printf("Polled for button press at %dms\r\n", xTaskGetTickCount()*portTICK_PERIOD_MS);
+        vTaskDelay(200 / portTICK_PERIOD_MS);
     }
 }
 
@@ -50,14 +50,14 @@ void buttonPollTask(void *pvParameters)
 void buttonIntTask(void *pvParameters)
 {
     printf("Waiting for button press interrupt on gpio %d...\r\n", gpio);
-    xQueueHandle *tsqueue = (xQueueHandle *)pvParameters;
+    QueueHandle_t *tsqueue = (QueueHandle_t *)pvParameters;
     gpio_set_interrupt(gpio, int_type);
 
     uint32_t last = 0;
     while(1) {
         uint32_t button_ts;
         xQueueReceive(*tsqueue, &button_ts, portMAX_DELAY);
-        button_ts *= portTICK_RATE_MS;
+        button_ts *= portTICK_PERIOD_MS;
         if(last < button_ts-200) {
             printf("Button interrupt fired at %dms\r\n", button_ts);
             last = button_ts;
@@ -65,7 +65,7 @@ void buttonIntTask(void *pvParameters)
     }
 }
 
-static xQueueHandle tsqueue;
+static QueueHandle_t tsqueue;
 
 void GPIO_HANDLER(void)
 {
diff --git a/examples/dht_sensor/dht_sensor.c b/examples/dht_sensor/dht_sensor.c
index 32988b1..22f110e 100644
--- a/examples/dht_sensor/dht_sensor.c
+++ b/examples/dht_sensor/dht_sensor.c
@@ -38,7 +38,7 @@ void dhtMeasurementTask(void *pvParameters)
         }
 
         // Three second delay...
-        vTaskDelay(3000 / portTICK_RATE_MS);
+        vTaskDelay(3000 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/ds18b20_broadcaster/ds18b20_broadcaster.c b/examples/ds18b20_broadcaster/ds18b20_broadcaster.c
index e5bcfea..5b7f1dc 100644
--- a/examples/ds18b20_broadcaster/ds18b20_broadcaster.c
+++ b/examples/ds18b20_broadcaster/ds18b20_broadcaster.c
@@ -88,7 +88,7 @@ void broadcast_temperature(void *pvParameters)
                 }
                 netbuf_delete(buf); // De-allocate packet buffer
             }
-            vTaskDelay(1000/portTICK_RATE_MS);
+            vTaskDelay(1000/portTICK_PERIOD_MS);
         }
 
         err = netconn_disconnect(conn);
@@ -97,7 +97,7 @@ void broadcast_temperature(void *pvParameters)
         err = netconn_delete(conn);
         printf("%s : Deleted connection (%s)\n", __FUNCTION__, lwip_strerr(err));
 
-        vTaskDelay(1000/portTICK_RATE_MS);
+        vTaskDelay(1000/portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/ds18b20_onewire/ds18b20_onewire.c b/examples/ds18b20_onewire/ds18b20_onewire.c
index 098f59f..73ff0b7 100644
--- a/examples/ds18b20_onewire/ds18b20_onewire.c
+++ b/examples/ds18b20_onewire/ds18b20_onewire.c
@@ -64,7 +64,7 @@ void print_temperature(void *pvParameters) {
                 // Wait for a little bit between each sample (note that the
                 // ds18b20_measure_and_read_multi operation already takes at
                 // least 750ms to run, so this is on top of that delay).
-                vTaskDelay(LOOP_DELAY_MS / portTICK_RATE_MS);
+                vTaskDelay(LOOP_DELAY_MS / portTICK_PERIOD_MS);
             }
         }
     }
diff --git a/examples/experiments/timers/timers.c b/examples/experiments/timers/timers.c
index bc3aa2b..a2e5e66 100644
--- a/examples/experiments/timers/timers.c
+++ b/examples/experiments/timers/timers.c
@@ -93,7 +93,7 @@ void timerRegTask(void *pvParameters)
         printf("frc2 handler called %d times, last value 0x%08x\r\n", frc2_handler_call_count,
                frc2_last_count_val);
 
-        vTaskDelay(500 / portTICK_RATE_MS);
+        vTaskDelay(500 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/experiments/unaligned_load/unaligned_load.c b/examples/experiments/unaligned_load/unaligned_load.c
index 984a566..f577ded 100644
--- a/examples/experiments/unaligned_load/unaligned_load.c
+++ b/examples/experiments/unaligned_load/unaligned_load.c
@@ -229,7 +229,7 @@ void user_init(void)
     test_isr();
     test_sign_extension();
 
-    xTaskHandle taskHandle;
+    TaskHandle_t taskHandle;
     xTaskCreate(test_system_interaction, "interactionTask", 256, &taskHandle, 2, NULL);
 }
 
@@ -304,7 +304,7 @@ static void test_system_interaction()
         */
     }
     uint32_t ticks = xTaskGetTickCount() - start;
-    printf("Timer interaction test PASSED after %dms.\n", ticks*portTICK_RATE_MS);
+    printf("Timer interaction test PASSED after %dms.\n", ticks*portTICK_PERIOD_MS);
     abort();
 }
 
diff --git a/examples/fatfs_rtc/main.c b/examples/fatfs_rtc/main.c
index 0c818d0..613eb6f 100644
--- a/examples/fatfs_rtc/main.c
+++ b/examples/fatfs_rtc/main.c
@@ -118,7 +118,7 @@ void rewrite_file_task(void *p)
         }
         while (false);
 
-        vTaskDelay(DELAY_MS / portTICK_RATE_MS);
+        vTaskDelay(DELAY_MS / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/http_get/http_get.c b/examples/http_get/http_get.c
index 408d5b1..0fe0ae1 100644
--- a/examples/http_get/http_get.c
+++ b/examples/http_get/http_get.c
@@ -43,7 +43,7 @@ void http_get_task(void *pvParameters)
             printf("DNS lookup failed err=%d res=%p\r\n", err, res);
             if(res)
                 freeaddrinfo(res);
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             failures++;
             continue;
         }
@@ -55,7 +55,7 @@ void http_get_task(void *pvParameters)
         if(s < 0) {
             printf("... Failed to allocate socket.\r\n");
             freeaddrinfo(res);
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
             failures++;
             continue;
         }
@@ -66,7 +66,7 @@ void http_get_task(void *pvParameters)
             close(s);
             freeaddrinfo(res);
             printf("... socket connect failed.\r\n");
-            vTaskDelay(4000 / portTICK_RATE_MS);
+            vTaskDelay(4000 / portTICK_PERIOD_MS);
             failures++;
             continue;
         }
@@ -81,7 +81,7 @@ void http_get_task(void *pvParameters)
         if (write(s, req, strlen(req)) < 0) {
             printf("... socket send failed\r\n");
             close(s);
-            vTaskDelay(4000 / portTICK_RATE_MS);
+            vTaskDelay(4000 / portTICK_PERIOD_MS);
             failures++;
             continue;
         }
@@ -106,7 +106,7 @@ void http_get_task(void *pvParameters)
         printf("successes = %d failures = %d\r\n", successes, failures);
         for(int countdown = 10; countdown >= 0; countdown--) {
             printf("%d... ", countdown);
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
         }
         printf("\r\nStarting again!\r\n");
     }
diff --git a/examples/http_get_mbedtls/http_get_mbedtls.c b/examples/http_get_mbedtls/http_get_mbedtls.c
index fa7c114..596a1f7 100644
--- a/examples/http_get_mbedtls/http_get_mbedtls.c
+++ b/examples/http_get_mbedtls/http_get_mbedtls.c
@@ -181,7 +181,7 @@ void http_get_task(void *pvParameters)
     err_t dns_err;
     ip_addr_t host_ip;
     do {
-        vTaskDelay(500 / portTICK_RATE_MS);
+        vTaskDelay(500 / portTICK_PERIOD_MS);
         dns_err = netconn_gethostbyname(WEB_SERVER, &host_ip);
     } while(dns_err != ERR_OK);
     printf("done.\n");
@@ -313,7 +313,7 @@ void http_get_task(void *pvParameters)
         printf("\n\nsuccesses = %d failures = %d\n", successes, failures);
         for(int countdown = successes ? 10 : 5; countdown >= 0; countdown--) {
             printf("%d... ", countdown);
-            vTaskDelay(1000 / portTICK_RATE_MS);
+            vTaskDelay(1000 / portTICK_PERIOD_MS);
         }
         printf("\nStarting again!\n");
     }
diff --git a/examples/i2s_audio/i2s_audio_example.c b/examples/i2s_audio/i2s_audio_example.c
index ddb1387..1972692 100644
--- a/examples/i2s_audio/i2s_audio_example.c
+++ b/examples/i2s_audio/i2s_audio_example.c
@@ -57,7 +57,7 @@ static dma_descriptor_t dma_block_list[DMA_QUEUE_SIZE];
 static uint8_t dma_buffer[DMA_QUEUE_SIZE][DMA_BUFFER_SIZE];
 
 // Queue of empty DMA blocks
-static xQueueHandle dma_queue;
+static QueueHandle_t dma_queue;
 
 /**
  * Create a circular list of DMA descriptors
@@ -183,7 +183,7 @@ void play_task(void *pvParameters)
 
         printf("underrun counter: %d\n", underrun_counter);
 
-        vTaskDelay(1000 / portTICK_RATE_MS);
+        vTaskDelay(1000 / portTICK_PERIOD_MS);
     }
 
     close(fd);
diff --git a/examples/mqtt_client/mqtt_client.c b/examples/mqtt_client/mqtt_client.c
index 2b9e764..6efbd2d 100644
--- a/examples/mqtt_client/mqtt_client.c
+++ b/examples/mqtt_client/mqtt_client.c
@@ -24,18 +24,18 @@
 #define MQTT_USER NULL
 #define MQTT_PASS NULL
 
-xSemaphoreHandle wifi_alive;
-xQueueHandle publish_queue;
+SemaphoreHandle_t wifi_alive;
+QueueHandle_t publish_queue;
 #define PUB_MSG_LEN 16
 
 static void  beat_task(void *pvParameters)
 {
-    portTickType xLastWakeTime = xTaskGetTickCount();
+    TickType_t xLastWakeTime = xTaskGetTickCount();
     char msg[PUB_MSG_LEN];
     int count = 0;
 
     while (1) {
-        vTaskDelayUntil(&xLastWakeTime, 10000 / portTICK_RATE_MS);
+        vTaskDelayUntil(&xLastWakeTime, 10000 / portTICK_PERIOD_MS);
         printf("beat\r\n");
         snprintf(msg, PUB_MSG_LEN, "Beat %d\r\n", count++);
         if (xQueueSend(publish_queue, (void *)msg, 0) == pdFALSE) {
@@ -190,7 +190,7 @@ static void  wifi_task(void *pvParameters)
                 printf("WiFi: connection failed\r\n");
                 break;
             }
-            vTaskDelay( 1000 / portTICK_RATE_MS );
+            vTaskDelay( 1000 / portTICK_PERIOD_MS );
             --retries;
         }
         if (status == STATION_GOT_IP) {
@@ -205,7 +205,7 @@ static void  wifi_task(void *pvParameters)
         }
         printf("WiFi: disconnected\n\r");
         sdk_wifi_station_disconnect();
-        vTaskDelay( 1000 / portTICK_RATE_MS );
+        vTaskDelay( 1000 / portTICK_PERIOD_MS );
     }
 }
 
diff --git a/examples/ota_basic/ota_basic.c b/examples/ota_basic/ota_basic.c
index 5083539..23102dd 100644
--- a/examples/ota_basic/ota_basic.c
+++ b/examples/ota_basic/ota_basic.c
@@ -109,10 +109,10 @@ void tftp_client_task(void *pvParameters)
     */
     while(1) {
         tftpclient_download_and_verify_file1(slot, &conf);
-        vTaskDelay(5000 / portTICK_RATE_MS);
+        vTaskDelay(5000 / portTICK_PERIOD_MS);
 
         tftpclient_download_file2(slot);
-        vTaskDelay(5000 / portTICK_RATE_MS);
+        vTaskDelay(5000 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/posix_fs/posix_fs_example.c b/examples/posix_fs/posix_fs_example.c
index 22877c4..610f58d 100644
--- a/examples/posix_fs/posix_fs_example.c
+++ b/examples/posix_fs/posix_fs_example.c
@@ -29,14 +29,14 @@ void test_task(void *pvParameters)
     esp_spiffs_mount();
 
     while (1) {
-        vTaskDelay(5000 / portTICK_RATE_MS);
+        vTaskDelay(5000 / portTICK_PERIOD_MS);
         if (fs_load_test_run(100)) {
             printf("PASS\n");
         } else {
             printf("FAIL\n");
         }
 
-        vTaskDelay(5000 / portTICK_RATE_MS);
+        vTaskDelay(5000 / portTICK_PERIOD_MS);
         float write_rate, read_rate;
         if (fs_speed_test_run(get_current_time, &write_rate, &read_rate)) {
             printf("Read speed: %.0f bytes/s\n", read_rate * 1000); 
diff --git a/examples/simple/simple.c b/examples/simple/simple.c
index 8134bb9..2f29df1 100644
--- a/examples/simple/simple.c
+++ b/examples/simple/simple.c
@@ -8,7 +8,7 @@
 
 void task1(void *pvParameters)
 {
-    xQueueHandle *queue = (xQueueHandle *)pvParameters;
+    QueueHandle_t *queue = (QueueHandle_t *)pvParameters;
     printf("Hello from task1!\r\n");
     uint32_t count = 0;
     while(1) {
@@ -21,7 +21,7 @@ void task1(void *pvParameters)
 void task2(void *pvParameters)
 {
     printf("Hello from task 2!\r\n");
-    xQueueHandle *queue = (xQueueHandle *)pvParameters;
+    QueueHandle_t *queue = (QueueHandle_t *)pvParameters;
     while(1) {
         uint32_t count;
         if(xQueueReceive(*queue, &count, 1000)) {
@@ -32,7 +32,7 @@ void task2(void *pvParameters)
     }
 }
 
-static xQueueHandle mainqueue;
+static QueueHandle_t mainqueue;
 
 void user_init(void)
 {
diff --git a/examples/sntp/sntp_example.c b/examples/sntp/sntp_example.c
index a68365a..0a933a2 100644
--- a/examples/sntp/sntp_example.c
+++ b/examples/sntp/sntp_example.c
@@ -27,7 +27,7 @@
 #define SNTP_SERVERS 	"0.pool.ntp.org", "1.pool.ntp.org", \
 						"2.pool.ntp.org", "3.pool.ntp.org"
 
-#define vTaskDelayMs(ms)	vTaskDelay((ms)/portTICK_RATE_MS)
+#define vTaskDelayMs(ms)	vTaskDelay((ms)/portTICK_PERIOD_MS)
 #define UNUSED_ARG(x)	(void)x
 
 void sntp_tsk(void *pvParameters)
diff --git a/examples/spiffs/spiffs_example.c b/examples/spiffs/spiffs_example.c
index 5252a92..2d0dcbf 100644
--- a/examples/spiffs/spiffs_example.c
+++ b/examples/spiffs/spiffs_example.c
@@ -96,7 +96,7 @@ void test_task(void *pvParameters)
     }
 
     while (1) {
-        vTaskDelay(2000 / portTICK_RATE_MS);
+        vTaskDelay(2000 / portTICK_PERIOD_MS);
 
         example_write_file();
 
diff --git a/examples/ssd1306_i2c/ssd1306_i2c.c b/examples/ssd1306_i2c/ssd1306_i2c.c
index 8ee64ba..7dadfb4 100644
--- a/examples/ssd1306_i2c/ssd1306_i2c.c
+++ b/examples/ssd1306_i2c/ssd1306_i2c.c
@@ -22,7 +22,7 @@ static uint8_t buffer[SSD1306_ROWS * SSD1306_COLS / 8];
 static void ssd1306_task(void *pvParameters)
 {
     printf("%s: Started user interface task\n", __FUNCTION__);
-    vTaskDelay(1000/portTICK_RATE_MS);
+    vTaskDelay(1000/portTICK_PERIOD_MS);
 
 
     if (ssd1306_load_xbm(image_bits, buffer))
@@ -30,14 +30,14 @@ static void ssd1306_task(void *pvParameters)
 
     ssd1306_set_whole_display_lighting(false);
     while (1) {
-        vTaskDelay(2000 / portTICK_RATE_MS);
+        vTaskDelay(2000 / portTICK_PERIOD_MS);
         printf("%s: steel alive\n", __FUNCTION__);
     }
 
 error_loop:
     printf("%s: error while loading framebuffer into SSD1306\n", __func__);
     for(;;){
-        vTaskDelay(2000 / portTICK_RATE_MS);
+        vTaskDelay(2000 / portTICK_PERIOD_MS);
         printf("%s: error loop\n", __FUNCTION__);
     }
 }
@@ -54,12 +54,12 @@ void user_init(void)
     if (ssd1306_init()){
         for (;;) {
             printf("%s: failed to init SSD1306 lcd\n", __func__);
-            vTaskDelay(1000/portTICK_RATE_MS);
+            vTaskDelay(1000/portTICK_PERIOD_MS);
         }
     }
 
     ssd1306_set_whole_display_lighting(true);
-    vTaskDelay(1000/portTICK_RATE_MS);
+    vTaskDelay(1000/portTICK_PERIOD_MS);
     // Create user interface task
     xTaskCreate(ssd1306_task, "ssd1306_task", 256, NULL, 2, NULL);
 }
diff --git a/examples/terminal/terminal.c b/examples/terminal/terminal.c
index 83ea734..6f8b940 100644
--- a/examples/terminal/terminal.c
+++ b/examples/terminal/terminal.c
@@ -59,7 +59,7 @@ static void cmd_help(uint32_t argc, char *argv[])
 static void cmd_sleep(uint32_t argc, char *argv[])
 {
     printf("Type away while I take a 2 second nap (ie. let you test the UART HW FIFO\n");
-    vTaskDelay(2000 / portTICK_RATE_MS);
+    vTaskDelay(2000 / portTICK_PERIOD_MS);
 }
 
 static void handle_command(char *cmd)
diff --git a/examples/tsl2561/tsl2561_example.c b/examples/tsl2561/tsl2561_example.c
index 447f669..b97804b 100644
--- a/examples/tsl2561/tsl2561_example.c
+++ b/examples/tsl2561/tsl2561_example.c
@@ -56,7 +56,7 @@ void tsl2561MeasurementTask(void *pvParameters)
         }
 
         // 0.1 second delay
-        vTaskDelay(100 / portTICK_RATE_MS);
+        vTaskDelay(100 / portTICK_PERIOD_MS);
     }
 }
 
diff --git a/examples/ws2812_i2s/ws2812_i2s_colour_loop.c b/examples/ws2812_i2s/ws2812_i2s_colour_loop.c
index 7644494..05f47c4 100644
--- a/examples/ws2812_i2s/ws2812_i2s_colour_loop.c
+++ b/examples/ws2812_i2s/ws2812_i2s_colour_loop.c
@@ -70,7 +70,7 @@ static void demo(void *pvParameters)
                     sizeof(ws2812_pixel_t));
 
             ws2812_i2s_update(pixels);
-            vTaskDelay(20 / portTICK_RATE_MS);
+            vTaskDelay(20 / portTICK_PERIOD_MS);
         }
     }
 }
diff --git a/examples/ws2812_rainbow/ws2812_rainbow.c b/examples/ws2812_rainbow/ws2812_rainbow.c
index 034b099..1f67775 100644
--- a/examples/ws2812_rainbow/ws2812_rainbow.c
+++ b/examples/ws2812_rainbow/ws2812_rainbow.c
@@ -18,7 +18,7 @@
 #include "ws2812.h"
 
 
-#define delay_ms(ms) vTaskDelay((ms) / portTICK_RATE_MS)
+#define delay_ms(ms) vTaskDelay((ms) / portTICK_PERIOD_MS)
 
 
 /** GPIO number used to control the RGBs */
diff --git a/extras/bmp180/README.md b/extras/bmp180/README.md
index a8c41f5..9da464b 100644
--- a/extras/bmp180/README.md
+++ b/extras/bmp180/README.md
@@ -34,7 +34,7 @@ As all data aqquired from the BMP180/BMP085 is provided to the `bmp180_informUse
 
 ```
 // Own BMP180 User Inform Implementation
-bool my_informUser(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure) {
+bool my_informUser(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure) {
 	my_event_t ev;
 
 	ev.event_type = MY_EVT_BMP180;
diff --git a/extras/bmp180/bmp180.c b/extras/bmp180/bmp180.c
index 805a620..c3c8afd 100644
--- a/extras/bmp180/bmp180.c
+++ b/extras/bmp180/bmp180.c
@@ -214,20 +214,20 @@ bool bmp180_measure(bmp180_constants_t *c, int32_t *temperature,
 typedef struct
 {
     uint8_t cmd;
-    const xQueueHandle* resultQueue;
+    const QueueHandle_t* resultQueue;
 } bmp180_command_t;
 
-// Just works due to the fact that xQueueHandle is a "void *"
-static xQueueHandle bmp180_rx_queue = NULL;
-static xTaskHandle  bmp180_task_handle = NULL;
+// Just works due to the fact that QueueHandle_t is a "void *"
+static QueueHandle_t bmp180_rx_queue = NULL;
+static TaskHandle_t bmp180_task_handle = NULL;
 
 //
 // Forward declarations
 //
-static bool bmp180_informUser_Impl(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure);
+static bool bmp180_informUser_Impl(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure);
 
 // Set default implementation .. User gets result as bmp180_result_t event
-bool (*bmp180_informUser)(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure) = bmp180_informUser_Impl;
+bool (*bmp180_informUser)(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure) = bmp180_informUser_Impl;
 
 // I2C Driver Task
 static void bmp180_driver_task(void *pvParameters)
@@ -295,7 +295,7 @@ static bool bmp180_createTask()
 }
 
 // Default user inform implementation
-static bool bmp180_informUser_Impl(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure)
+static bool bmp180_informUser_Impl(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure)
 {
     bmp180_result_t result;
 
@@ -328,7 +328,7 @@ bool bmp180_init(uint8_t scl, uint8_t sda)
     return result;
 }
 
-void bmp180_trigger_measurement(const xQueueHandle* resultQueue)
+void bmp180_trigger_measurement(const QueueHandle_t* resultQueue)
 {
     bmp180_command_t c;
 
@@ -339,7 +339,7 @@ void bmp180_trigger_measurement(const xQueueHandle* resultQueue)
 }
 
 
-void bmp180_trigger_pressure_measurement(const xQueueHandle* resultQueue)
+void bmp180_trigger_pressure_measurement(const QueueHandle_t* resultQueue)
 {
     bmp180_command_t c;
 
@@ -349,7 +349,7 @@ void bmp180_trigger_pressure_measurement(const xQueueHandle* resultQueue)
     xQueueSend(bmp180_rx_queue, &c, 0);
 }
 
-void bmp180_trigger_temperature_measurement(const xQueueHandle* resultQueue)
+void bmp180_trigger_temperature_measurement(const QueueHandle_t* resultQueue)
 {
     bmp180_command_t c;
 
diff --git a/extras/bmp180/bmp180.h b/extras/bmp180/bmp180.h
index e7fc470..2f46150 100644
--- a/extras/bmp180/bmp180.h
+++ b/extras/bmp180/bmp180.h
@@ -45,16 +45,16 @@ typedef struct
 bool bmp180_init(uint8_t scl, uint8_t sda);
 
 // Trigger a "complete" measurement (temperature and pressure will be valid when given to "bmp180_informUser)
-void bmp180_trigger_measurement(const xQueueHandle* resultQueue);
+void bmp180_trigger_measurement(const QueueHandle_t* resultQueue);
 
 // Trigger a "temperature only" measurement (only temperature will be valid when given to "bmp180_informUser)
-void bmp180_trigger_temperature_measurement(const xQueueHandle* resultQueue);
+void bmp180_trigger_temperature_measurement(const QueueHandle_t* resultQueue);
 
 // Trigger a "pressure only" measurement (only pressure will be valid when given to "bmp180_informUser)
-void bmp180_trigger_pressure_measurement(const xQueueHandle* resultQueue);
+void bmp180_trigger_pressure_measurement(const QueueHandle_t* resultQueue);
 
 // Give the user the chance to create it's own handler
-extern bool (*bmp180_informUser)(const xQueueHandle* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure);
+extern bool (*bmp180_informUser)(const QueueHandle_t* resultQueue, uint8_t cmd, bmp180_temp_t temperature, bmp180_press_t pressure);
 
 // Calibration constants
 typedef struct
diff --git a/extras/bmp280/README.md b/extras/bmp280/README.md
index 9faed88..09e0115 100644
--- a/extras/bmp280/README.md
+++ b/extras/bmp280/README.md
@@ -72,7 +72,7 @@ while(1) {
   printf("Pressure: %.2f Pa, Temperature: %.2f C", pressure, temperature);
   if (bme280p)
     printf(", Humidity: %.2f\n", humidity);
-  vTaskDelay(1000 / portTICK_RATE_MS);
+  vTaskDelay(1000 / portTICK_PERIOD_MS);
 }
 ```
 
@@ -96,7 +96,7 @@ while(1) {
     printf(", Humidity: %.2f\n", humidity);
   else
     printf("\n");
-  vTaskDelay(1000 / portTICK_RATE_MS);
+  vTaskDelay(1000 / portTICK_PERIOD_MS);
 }
 ```
 
diff --git a/extras/cpp_support/include/countdown.hpp b/extras/cpp_support/include/countdown.hpp
index 87c8f3f..81f3853 100644
--- a/extras/cpp_support/include/countdown.hpp
+++ b/extras/cpp_support/include/countdown.hpp
@@ -35,7 +35,7 @@
 namespace esp_open_rtos {
 namespace timer {
 
-#define __millis()  (xTaskGetTickCount() * portTICK_RATE_MS)
+#define __millis()  (xTaskGetTickCount() * portTICK_PERIOD_MS)
 
 /******************************************************************************************************************
  * countdown_t
@@ -93,7 +93,7 @@ public:
     }
     
 private:
-    portTickType interval_end_ms;
+    TickType_t interval_end_ms;
 };
 
 } // namespace timer {
diff --git a/extras/cpp_support/include/mutex.hpp b/extras/cpp_support/include/mutex.hpp
index aaf29db..62b490c 100644
--- a/extras/cpp_support/include/mutex.hpp
+++ b/extras/cpp_support/include/mutex.hpp
@@ -86,7 +86,7 @@ public:
      */
     inline int try_lock(unsigned long ms)
     {
-        return (xSemaphoreTake(mutex, ms / portTICK_RATE_MS) == pdTRUE) ? 0 : -1;
+        return (xSemaphoreTake(mutex, ms / portTICK_PERIOD_MS) == pdTRUE) ? 0 : -1;
     }
     /**
      * 
@@ -98,7 +98,7 @@ public:
     }
 
 private:
-    xSemaphoreHandle    mutex;
+    SemaphoreHandle_t    mutex;
 
     // Disable copy construction and assignment.
     mutex_t (const mutex_t&);
diff --git a/extras/cpp_support/include/queue.hpp b/extras/cpp_support/include/queue.hpp
index 047ce29..38a0493 100644
--- a/extras/cpp_support/include/queue.hpp
+++ b/extras/cpp_support/include/queue.hpp
@@ -83,7 +83,7 @@ public:
      */
     inline int post(const Data& data, unsigned long ms = 0)
     {
-        return (xQueueSend(queue, &data, ms / portTICK_RATE_MS) == pdTRUE) ? 0 : -1;
+        return (xQueueSend(queue, &data, ms / portTICK_PERIOD_MS) == pdTRUE) ? 0 : -1;
     }
     /**
      * 
@@ -93,7 +93,7 @@ public:
      */
     inline int receive(Data& data, unsigned long ms = 0)
     {
-        return (xQueueReceive(queue, &data, ms / portTICK_RATE_MS) == pdTRUE) ? 0 : -1;
+        return (xQueueReceive(queue, &data, ms / portTICK_PERIOD_MS) == pdTRUE) ? 0 : -1;
     }
     /**
      * 
@@ -110,7 +110,7 @@ public:
     }
 
 private:
-    xQueueHandle queue;
+    QueueHandle_t queue;
 
     // Disable copy construction.
     queue_t (const queue_t&);
diff --git a/extras/cpp_support/include/task.hpp b/extras/cpp_support/include/task.hpp
index e87e32a..75a716d 100644
--- a/extras/cpp_support/include/task.hpp
+++ b/extras/cpp_support/include/task.hpp
@@ -66,7 +66,7 @@ protected:
      */
     void sleep(unsigned long ms)
     {
-        vTaskDelay(ms / portTICK_RATE_MS);
+        vTaskDelay(ms / portTICK_PERIOD_MS);
     }
     /**
      * 
@@ -74,7 +74,7 @@ protected:
      */
     inline unsigned long millis()
     {
-        return xTaskGetTickCount() * portTICK_RATE_MS;
+        return xTaskGetTickCount() * portTICK_PERIOD_MS;
     }
     
 private:
diff --git a/extras/dhcpserver/dhcpserver.c b/extras/dhcpserver/dhcpserver.c
index f1e8f66..d87daab 100644
--- a/extras/dhcpserver/dhcpserver.c
+++ b/extras/dhcpserver/dhcpserver.c
@@ -49,7 +49,7 @@ typedef struct {
 /* Only one DHCP server task can run at once, so we have global state
    for it.
 */
-static xTaskHandle dhcpserver_task_handle=NULL;
+static TaskHandle_t dhcpserver_task_handle = NULL;
 static server_state_t *state;
 
 /* Handlers for various kinds of incoming DHCP messages */
diff --git a/extras/ds18b20/ds18b20.c b/extras/ds18b20/ds18b20.c
index 466422e..36449d7 100644
--- a/extras/ds18b20/ds18b20.c
+++ b/extras/ds18b20/ds18b20.c
@@ -16,7 +16,7 @@
 #define DS18B20_ALARMSEARCH      0xEC
 #define DS18B20_CONVERT_T        0x44
 
-#define os_sleep_ms(x) vTaskDelay(((x) + portTICK_RATE_MS - 1) / portTICK_RATE_MS)
+#define os_sleep_ms(x) vTaskDelay(((x) + portTICK_PERIOD_MS - 1) / portTICK_PERIOD_MS)
 
 #define DS18B20_FAMILY_ID 0x28
 #define DS18S20_FAMILY_ID 0x10
@@ -46,7 +46,7 @@ uint8_t ds18b20_read_all(uint8_t pin, ds_sensor_t *result) {
         onewire_write(pin, DS18B20_CONVERT_T);
         
         onewire_power(pin);
-        vTaskDelay(750 / portTICK_RATE_MS);
+        vTaskDelay(750 / portTICK_PERIOD_MS);
         
         onewire_reset(pin);
         onewire_select(pin, addr);
@@ -88,7 +88,7 @@ float ds18b20_read_single(uint8_t pin) {
     onewire_write(pin, DS18B20_CONVERT_T);
 
     onewire_power(pin);
-    vTaskDelay(750 / portTICK_RATE_MS);
+    vTaskDelay(750 / portTICK_PERIOD_MS);
 
     onewire_reset(pin);
     onewire_skip_rom(pin);
diff --git a/extras/fatfs/ffconf.h b/extras/fatfs/ffconf.h
index 00b79a4..7962e2a 100644
--- a/extras/fatfs/ffconf.h
+++ b/extras/fatfs/ffconf.h
@@ -275,7 +275,7 @@
 #ifndef _FS_TIMEOUT
 #define _FS_TIMEOUT		1000
 #endif
-#define _SYNC_t         xSemaphoreHandle
+#define _SYNC_t         SemaphoreHandle_t
 /* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
 /  module itself. Note that regardless of this option, file access to different
 /  volume is always re-entrant and volume control functions, f_mount(), f_mkfs()
diff --git a/extras/fatfs/syscall.c b/extras/fatfs/syscall.c
index 0fff89a..eb54f37 100644
--- a/extras/fatfs/syscall.c
+++ b/extras/fatfs/syscall.c
@@ -13,7 +13,7 @@
  * synchronization object, such as semaphore and mutex. When a 0 is returned,
  * the f_mount() function fails with FR_INT_ERR.
  */
-int ff_cre_syncobj(BYTE vol, xSemaphoreHandle *sobj)
+int ff_cre_syncobj(BYTE vol, SemaphoreHandle_t *sobj)
 {
     int ret;
 
@@ -29,7 +29,7 @@ int ff_cre_syncobj(BYTE vol, xSemaphoreHandle *sobj)
  * object that created with ff_cre_syncobj() function. When a 0 is returned,
  * the f_mount() function fails with FR_INT_ERR.
  */
-int ff_del_syncobj(xSemaphoreHandle sobj)
+int ff_del_syncobj(SemaphoreHandle_t sobj)
 {
     vSemaphoreDelete(sobj);
     return 1;
@@ -40,7 +40,7 @@ int ff_del_syncobj(xSemaphoreHandle sobj)
  * This function is called on entering file functions to lock the volume.
  * When a 0 is returned, the file function fails with FR_TIMEOUT.
  */
-int ff_req_grant(xSemaphoreHandle sobj)
+int ff_req_grant(SemaphoreHandle_t sobj)
 {
     return (int)(xSemaphoreTake(sobj, _FS_TIMEOUT) == pdTRUE);
 }
@@ -49,7 +49,7 @@ int ff_req_grant(xSemaphoreHandle sobj)
  * Release Grant to Access the Volume
  * This function is called on leaving file functions to unlock the volume.
  */
-void ff_rel_grant(xSemaphoreHandle sobj)
+void ff_rel_grant(SemaphoreHandle_t sobj)
 {
     xSemaphoreGive(sobj);
 }
diff --git a/extras/paho_mqtt_c/MQTTESP8266.c b/extras/paho_mqtt_c/MQTTESP8266.c
index 83e257f..e7a14d9 100644
--- a/extras/paho_mqtt_c/MQTTESP8266.c
+++ b/extras/paho_mqtt_c/MQTTESP8266.c
@@ -30,7 +30,7 @@
 
 char  mqtt_timer_expired(mqtt_timer_t* timer)
 {
-    portTickType now = xTaskGetTickCount();
+    TickType_t now = xTaskGetTickCount();
     int32_t left = timer->end_time - now;
     return (left < 0);
 }
@@ -38,8 +38,8 @@ char  mqtt_timer_expired(mqtt_timer_t* timer)
 
 void  mqtt_timer_countdown_ms(mqtt_timer_t* timer, unsigned int timeout)
 {
-    portTickType now = xTaskGetTickCount();
-    timer->end_time = now + timeout / portTICK_RATE_MS;
+    TickType_t now = xTaskGetTickCount();
+    timer->end_time = now + timeout / portTICK_PERIOD_MS;
 }
 
 
@@ -51,9 +51,9 @@ void  mqtt_timer_countdown(mqtt_timer_t* timer, unsigned int timeout)
 
 int  mqtt_timer_left_ms(mqtt_timer_t* timer)
 {
-    portTickType now = xTaskGetTickCount();
+    TickType_t now = xTaskGetTickCount();
     int32_t left = timer->end_time - now;
-    return (left < 0) ? 0 : left / portTICK_RATE_MS;
+    return (left < 0) ? 0 : left / portTICK_PERIOD_MS;
 }
 
 
@@ -73,7 +73,7 @@ int  mqtt_esp_read(mqtt_network_t* n, unsigned char* buffer, int len, int timeou
     FD_ZERO(&fdset);
     FD_SET(n->my_socket, &fdset);
     // It seems tv_sec actually means FreeRTOS tick
-    tv.tv_sec = timeout_ms / portTICK_RATE_MS;
+    tv.tv_sec = timeout_ms / portTICK_PERIOD_MS;
     tv.tv_usec = 0;
     rc = select(n->my_socket + 1, &fdset, 0, 0, &tv);
     if ((rc > 0) && (FD_ISSET(n->my_socket, &fdset)))
@@ -98,7 +98,7 @@ int  mqtt_esp_write(mqtt_network_t* n, unsigned char* buffer, int len, int timeo
     FD_ZERO(&fdset);
     FD_SET(n->my_socket, &fdset);
     // It seems tv_sec actually means FreeRTOS tick
-    tv.tv_sec = timeout_ms / portTICK_RATE_MS;
+    tv.tv_sec = timeout_ms / portTICK_PERIOD_MS;
     tv.tv_usec = 0;
     rc = select(n->my_socket + 1, 0, &fdset, 0, &tv);
     if ((rc > 0) && (FD_ISSET(n->my_socket, &fdset)))
diff --git a/extras/paho_mqtt_c/MQTTESP8266.h b/extras/paho_mqtt_c/MQTTESP8266.h
index 18e9cdf..05380e8 100644
--- a/extras/paho_mqtt_c/MQTTESP8266.h
+++ b/extras/paho_mqtt_c/MQTTESP8266.h
@@ -28,7 +28,7 @@ typedef struct mqtt_timer mqtt_timer_t;
 
 struct mqtt_timer
 {
-    portTickType end_time;
+    TickType_t end_time;
 };
 
 typedef struct mqtt_network mqtt_network_t;
diff --git a/extras/stdin_uart_interrupt/stdin_uart_interrupt.c b/extras/stdin_uart_interrupt/stdin_uart_interrupt.c
index c836651..3319588 100644
--- a/extras/stdin_uart_interrupt/stdin_uart_interrupt.c
+++ b/extras/stdin_uart_interrupt/stdin_uart_interrupt.c
@@ -40,7 +40,7 @@
 
 #define UART0_RX_SIZE  (128) // ESP8266 UART HW FIFO size
 
-static xSemaphoreHandle uart0_sem = NULL;
+static SemaphoreHandle_t uart0_sem = NULL;
 static bool inited = false;
 static void uart0_rx_init(void);
 
diff --git a/extras/tsl2561/tsl2561.c b/extras/tsl2561/tsl2561.c
index 6a8ac74..36c52e9 100644
--- a/extras/tsl2561/tsl2561.c
+++ b/extras/tsl2561/tsl2561.c
@@ -195,13 +195,13 @@ static void get_channel_data(tsl2561_t *device, uint16_t *channel0, uint16_t *ch
     switch (device->integration_time)
     {
         case TSL2561_INTEGRATION_13MS:
-            vTaskDelay(TSL2561_INTEGRATION_TIME_13MS / portTICK_RATE_MS);
+            vTaskDelay(TSL2561_INTEGRATION_TIME_13MS / portTICK_PERIOD_MS);
             break;
         case TSL2561_INTEGRATION_101MS:
-            vTaskDelay(TSL2561_INTEGRATION_TIME_101MS / portTICK_RATE_MS);
+            vTaskDelay(TSL2561_INTEGRATION_TIME_101MS / portTICK_PERIOD_MS);
             break;
         default:
-            vTaskDelay(TSL2561_INTEGRATION_TIME_402MS / portTICK_RATE_MS);
+            vTaskDelay(TSL2561_INTEGRATION_TIME_402MS / portTICK_PERIOD_MS);
             break;
     }
 
diff --git a/include/etstimer.h b/include/etstimer.h
index 1187ab9..36e1a59 100644
--- a/include/etstimer.h
+++ b/include/etstimer.h
@@ -28,7 +28,7 @@ typedef void ETSTimerFunc(void *);
 
 typedef struct ETSTimer_st {
     struct ETSTimer_st  *timer_next;
-    xTimerHandle timer_handle;
+    TimerHandle_t timer_handle;
     uint32_t _unknown;
     uint32_t timer_ms;
     ETSTimerFunc *timer_func;
diff --git a/lwip/include/arch/sys_arch.h b/lwip/include/arch/sys_arch.h
index ac616c9..0dfa482 100644
--- a/lwip/include/arch/sys_arch.h
+++ b/lwip/include/arch/sys_arch.h
@@ -39,14 +39,14 @@
 
 /* MBOX primitives */
 
-#define SYS_MBOX_NULL					( ( xQueueHandle ) NULL )
-#define SYS_SEM_NULL					( ( xSemaphoreHandle ) NULL )
+#define SYS_MBOX_NULL					( ( QueueHandle_t ) NULL )
+#define SYS_SEM_NULL					( ( SemaphoreHandle_t ) NULL )
 #define SYS_DEFAULT_THREAD_STACK_DEPTH	configMINIMAL_STACK_SIZE
 
-typedef xSemaphoreHandle sys_sem_t;
-typedef xSemaphoreHandle sys_mutex_t;
-typedef xQueueHandle sys_mbox_t;
-typedef xTaskHandle sys_thread_t;
+typedef SemaphoreHandle_t sys_sem_t;
+typedef SemaphoreHandle_t sys_mutex_t;
+typedef QueueHandle_t sys_mbox_t;
+typedef TaskHandle_t sys_thread_t;
 
 #define sys_mbox_valid( x ) ( ( ( *x ) == NULL) ? pdFALSE : pdTRUE )
 #define sys_mbox_set_invalid( x ) ( ( *x ) = NULL )
diff --git a/lwip/sys_arch.c b/lwip/sys_arch.c
index 51c29e0..87d8450 100644
--- a/lwip/sys_arch.c
+++ b/lwip/sys_arch.c
@@ -159,7 +159,7 @@ portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
     }
     else
     {
-        xReturn = xQueueSend( *pxMailBox, &pxMessageToPost, ( portTickType ) 0 );
+        xReturn = xQueueSend( *pxMailBox, &pxMessageToPost, ( TickType_t ) 0 );
     }
 
     if( xReturn == pdPASS )
@@ -204,7 +204,7 @@ portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
 u32_t sys_arch_mbox_fetch( sys_mbox_t *pxMailBox, void **ppvBuffer, u32_t ulTimeOut )
 {
 void *pvDummy;
-portTickType xStartTime, xEndTime, xElapsed;
+TickType_t xStartTime, xEndTime, xElapsed;
 unsigned long ulReturn;
 
     xStartTime = xTaskGetTickCount();
@@ -218,10 +218,10 @@ unsigned long ulReturn;
     {
         configASSERT( is_inside_isr() == ( portBASE_TYPE ) 0 );
 
-        if( pdTRUE == xQueueReceive( *pxMailBox, &( *ppvBuffer ), ulTimeOut/ portTICK_RATE_MS ) )
+        if( pdTRUE == xQueueReceive( *pxMailBox, &( *ppvBuffer ), ulTimeOut/ portTICK_PERIOD_MS ) )
         {
             xEndTime = xTaskGetTickCount();
-            xElapsed = ( xEndTime - xStartTime ) * portTICK_RATE_MS;
+            xElapsed = ( xEndTime - xStartTime ) * portTICK_PERIOD_MS;
 
             ulReturn = xElapsed;
         }
@@ -236,7 +236,7 @@ unsigned long ulReturn;
     {
         while( pdTRUE != xQueueReceive( *pxMailBox, &( *ppvBuffer ), portMAX_DELAY ) );
         xEndTime = xTaskGetTickCount();
-        xElapsed = ( xEndTime - xStartTime ) * portTICK_RATE_MS;
+        xElapsed = ( xEndTime - xStartTime ) * portTICK_PERIOD_MS;
 
         if( xElapsed == 0UL )
         {
@@ -358,17 +358,17 @@ err_t xReturn = ERR_MEM;
  *---------------------------------------------------------------------------*/
 u32_t sys_arch_sem_wait( sys_sem_t *pxSemaphore, u32_t ulTimeout )
 {
-portTickType xStartTime, xEndTime, xElapsed;
+TickType_t xStartTime, xEndTime, xElapsed;
 unsigned long ulReturn;
 
     xStartTime = xTaskGetTickCount();
 
     if( ulTimeout != 0UL )
     {
-        if( xSemaphoreTake( *pxSemaphore, ulTimeout / portTICK_RATE_MS ) == pdTRUE )
+        if( xSemaphoreTake( *pxSemaphore, ulTimeout / portTICK_PERIOD_MS ) == pdTRUE )
         {
             xEndTime = xTaskGetTickCount();
-            xElapsed = (xEndTime - xStartTime) * portTICK_RATE_MS;
+            xElapsed = (xEndTime - xStartTime) * portTICK_PERIOD_MS;
             ulReturn = xElapsed;
         }
         else
@@ -380,7 +380,7 @@ unsigned long ulReturn;
     {
         while( xSemaphoreTake( *pxSemaphore, portMAX_DELAY ) != pdTRUE );
         xEndTime = xTaskGetTickCount();
-        xElapsed = ( xEndTime - xStartTime ) * portTICK_RATE_MS;
+        xElapsed = ( xEndTime - xStartTime ) * portTICK_PERIOD_MS;
 
         if( xElapsed == 0UL )
         {
@@ -487,7 +487,7 @@ void sys_init(void)
 
 u32_t sys_now(void)
 {
-    return xTaskGetTickCount() * portTICK_RATE_MS;
+    return xTaskGetTickCount() * portTICK_PERIOD_MS;
 }
 
 /*---------------------------------------------------------------------------*
@@ -510,7 +510,7 @@ u32_t sys_now(void)
  *---------------------------------------------------------------------------*/
 sys_thread_t sys_thread_new( const char *pcName, void( *pxThread )( void *pvParameters ), void *pvArg, int iStackSize, int iPriority )
 {
-xTaskHandle xCreatedTask;
+TaskHandle_t xCreatedTask;
 portBASE_TYPE xResult;
 sys_thread_t xReturn;
 
diff --git a/open_esplibs/libmain/os_cpu_a.c b/open_esplibs/libmain/os_cpu_a.c
index 9ace3a8..7fd3719 100644
--- a/open_esplibs/libmain/os_cpu_a.c
+++ b/open_esplibs/libmain/os_cpu_a.c
@@ -72,7 +72,7 @@ void IRAM sdk__xt_int_exit(void) {
 void IRAM sdk__xt_timer_int(void) {
     uint32_t trigger_ccount;
     uint32_t current_ccount;
-    uint32_t ccount_interval = portTICK_RATE_MS * sdk_os_get_cpu_frequency() * 1000;
+    uint32_t ccount_interval = portTICK_PERIOD_MS * sdk_os_get_cpu_frequency() * 1000;
 
     do {
         RSR(trigger_ccount, ccompare0);
@@ -93,7 +93,7 @@ void IRAM sdk__xt_timer_int1(void) {
 void IRAM sdk__xt_tick_timer_init(void) {
     uint32_t ints_enabled;
     uint32_t current_ccount;
-    uint32_t ccount_interval = portTICK_RATE_MS * sdk_os_get_cpu_frequency() * 1000;
+    uint32_t ccount_interval = portTICK_PERIOD_MS * sdk_os_get_cpu_frequency() * 1000;
 
     RSR(current_ccount, ccount);
     WSR(current_ccount + ccount_interval, ccompare0);
diff --git a/open_esplibs/libmain/timers.c b/open_esplibs/libmain/timers.c
index b30f6e3..42a6767 100644
--- a/open_esplibs/libmain/timers.c
+++ b/open_esplibs/libmain/timers.c
@@ -60,7 +60,7 @@ void sdk_os_timer_setfn(ETSTimer *ptimer, ETSTimerFunc *pfunction, void *parg) {
     *tailptr = new_entry;
 }
 
-static void timer_tramp(xTimerHandle xTimer)
+static void timer_tramp(TimerHandle_t xTimer)
 {
     ETSTimer *ptimer = pvTimerGetTimerID(xTimer);
     ptimer->timer_func(ptimer->timer_arg);