From ca32c8a8730eedacf8f7fd65134c67ee582be8a5 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 7 Jan 2024 16:19:48 +1000 Subject: [PATCH] AP_HAL_ESP32 : this was an attempt at resolving watchdog issues , now just needs to go superceeded by https://github.com/ArduPilot/ardupilot/commit/b9ac504d0daa4e370e5b8660b618005b31a16796 --- libraries/AP_HAL_ESP32/Scheduler.cpp | 2 +- libraries/AP_HAL_ESP32/SdCard.cpp | 4 ---- libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp | 2 -- 3 files changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index 8a30f612eb..976b7245fd 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -235,7 +235,7 @@ void Scheduler::delay_microseconds(uint16_t us) ets_delay_us(us); } else { // Minimum delay for FreeRTOS is 1ms uint32_t tick = portTICK_PERIOD_MS * 1000; - rtc_wdt_feed(); + vTaskDelay((us+tick-1)/tick); } } diff --git a/libraries/AP_HAL_ESP32/SdCard.cpp b/libraries/AP_HAL_ESP32/SdCard.cpp index 725235fba9..0f91711e1a 100644 --- a/libraries/AP_HAL_ESP32/SdCard.cpp +++ b/libraries/AP_HAL_ESP32/SdCard.cpp @@ -165,9 +165,7 @@ void mount_sdcard_mmc() // Please check its source code and implement error recovery when developing // production applications. sdmmc_card_t* card; - rtc_wdt_feed(); esp_err_t ret = esp_vfs_fat_sdmmc_mount("/SDCARD", &host, &slot_config, &mount_config, &card); - rtc_wdt_feed(); if (ret == ESP_OK) { mkdir("/SDCARD/APM", 0777); @@ -237,9 +235,7 @@ void mount_sdcard_spi() //host.flags = SDMMC_HOST_FLAG_1BIT | SDMMC_HOST_FLAG_DDR; host.max_freq_khz = SDMMC_FREQ_PROBING; - rtc_wdt_feed(); ret = esp_vfs_fat_sdspi_mount("/SDCARD", &host, &slot_config, &mount_config, &card); - rtc_wdt_feed(); if (ret == ESP_OK) { // Card has been initialized, print its properties diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index b7a48f4f94..7352254d85 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -351,10 +351,8 @@ void WiFiUdpDriver::_wifi_thread2(void *arg) .tv_usec = 100*1000, // 10 times a sec, we try to write-all even if we read nothing , at just 1000, it floggs the APM_WIFI2 task cpu usage unecessarily, slowing APM_WIFI1 response }; fd_set rfds; - rtc_wdt_feed(); FD_ZERO(&rfds); FD_SET(self->accept_socket, &rfds); - rtc_wdt_feed(); int s = select(self->accept_socket + 1, &rfds, NULL, NULL, &tv); if (s > 0 && FD_ISSET(self->accept_socket, &rfds)) { self->read_all();