diff --git a/libraries/AP_HAL_ESP32/WiFiDriver.cpp b/libraries/AP_HAL_ESP32/WiFiDriver.cpp index f1c7eb9e97276..fbc9e85ddb839 100644 --- a/libraries/AP_HAL_ESP32/WiFiDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiDriver.cpp @@ -56,10 +56,10 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) #define FASTCPU 0 #define SLOWCPU 1 - if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread on FASTCPU\n"); + if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle, SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread for TCP with PORT 5760 on FASTCPU\n"); + hal.console->printf("OK created task _wifi_thread for TCP with PORT 5760 on SLOWCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index d6a247e13c5d6..2d97b4f491008 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -59,10 +59,10 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) #define FASTCPU 0 #define SLOWCPU 1 - if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread2 on FASTCPU\n"); + if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle, SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread2 on SLOWCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread2 for UDP on port 14550 on FASTCPU\n"); //UDP_PORT + hal.console->printf("OK created task _wifi_thread2 for UDP on port 14550 on SLOWCPU\n"); //UDP_PORT } _readbuf.set_size(RX_BUF_SIZE);