Skip to content

Commit

Permalink
AP_HAL_ESP32: Switch WIFI task from FASTCPU to SLOWCPU
Browse files Browse the repository at this point in the history
Switching WIFI task from FASTCPU to SLOWCPU seems to bring more balance between CPUs and thus increasing connection reliabiiity
  • Loading branch information
sblaksono committed Oct 24, 2024
1 parent 92693e0 commit af31fae
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_HAL_ESP32/WiFiDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit af31fae

Please sign in to comment.