AP_HAL_ESP32: Switch WIFI task from FASTCPU to SLOWCPU

Switching WIFI task from FASTCPU to SLOWCPU seems to bring more balance between CPUs and thus increasing connection reliabiiity
This commit is contained in:
Bayu Laksono 2024-10-05 12:17:04 +07:00 committed by Peter Barker
parent 380e9aa36b
commit d27742983f
2 changed files with 6 additions and 6 deletions

View File

@ -56,10 +56,10 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
#define FASTCPU 0 #define FASTCPU 0
#define SLOWCPU 1 #define SLOWCPU 1
if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) { 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 FASTCPU\n"); hal.console->printf("FAILED to create task _wifi_thread on SLOWCPU\n");
} else { } 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); _readbuf.set_size(RX_BUF_SIZE);

View File

@ -59,10 +59,10 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
#define FASTCPU 0 #define FASTCPU 0
#define SLOWCPU 1 #define SLOWCPU 1
if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) { 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 FASTCPU\n"); hal.console->printf("FAILED to create task _wifi_thread2 on SLOWCPU\n");
} else { } 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); _readbuf.set_size(RX_BUF_SIZE);