mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32 : this was an attempt at resolving watchdog issues , now just needs to go
superceeded by b9ac504d0d
This commit is contained in:
parent
57ccac308d
commit
ca32c8a873
|
@ -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);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue