From b9ac504d0daa4e370e5b8660b618005b31a16796 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sat, 6 Jan 2024 13:38:57 +1000 Subject: [PATCH] AP_HAL_ESP32: prevent watchdog while booting with slow things like sdcards --- libraries/AP_HAL_ESP32/README.md | 6 +- libraries/AP_HAL_ESP32/Scheduler.cpp | 81 ++++++++++++------- libraries/AP_HAL_ESP32/SdCard.cpp | 7 +- libraries/AP_HAL_ESP32/WiFiDriver.cpp | 11 ++- libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp | 16 +++- .../targets/esp32/esp-idf/sdkconfig | 43 +++++++++- 6 files changed, 125 insertions(+), 39 deletions(-) diff --git a/libraries/AP_HAL_ESP32/README.md b/libraries/AP_HAL_ESP32/README.md index de2fbe7e70..e891fa9571 100644 --- a/libraries/AP_HAL_ESP32/README.md +++ b/libraries/AP_HAL_ESP32/README.md @@ -96,8 +96,10 @@ ESPBAUD=921600 ./waf plane --upload You can use your default build system (make or ninja) to build other esp-idf target. For example : -- ninja flash -- ninja monitor + source modules/esp_idf/export.sh + cd /home/buzz2/ardupilot/build/esp32buzz/esp-idf_build + ninja flash + ninja monitor If you want to specify the port, specify before any command: ``` diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index 9b940f9c9f..8a30f612eb 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -38,6 +38,8 @@ using namespace ESP32; extern const AP_HAL::HAL& hal; bool Scheduler::_initialized = true; +TaskHandle_t idle_0 = NULL; +TaskHandle_t idle_1 = NULL; Scheduler::Scheduler() { @@ -46,7 +48,7 @@ Scheduler::Scheduler() void disableCore0WDT() { - TaskHandle_t idle_0 = xTaskGetIdleTaskHandleForCPU(0); + idle_0 = xTaskGetIdleTaskHandleForCPU(0); if (idle_0 == NULL || esp_task_wdt_delete(idle_0) != ESP_OK) { //print("Failed to remove Core 0 IDLE task from WDT"); } @@ -54,11 +56,23 @@ void disableCore0WDT() void disableCore1WDT() { - TaskHandle_t idle_1 = xTaskGetIdleTaskHandleForCPU(1); + idle_1 = xTaskGetIdleTaskHandleForCPU(1); if (idle_1 == NULL || esp_task_wdt_delete(idle_1) != ESP_OK) { //print("Failed to remove Core 1 IDLE task from WDT"); } } +void enableCore0WDT() +{ + if (idle_0 != NULL && esp_task_wdt_add(idle_0) != ESP_OK) { + //print("Failed to add Core 0 IDLE task to WDT"); + } +} +void enableCore1WDT() +{ + if (idle_1 != NULL && esp_task_wdt_add(idle_1) != ESP_OK) { + //print("Failed to add Core 1 IDLE task to WDT"); + } +} void Scheduler::init() { @@ -67,57 +81,69 @@ void Scheduler::init() printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); #endif + // disable wd while booting, as things like mounting the sd-card in the io thread can take a while, especially if there isn't hardware attached. + disableCore0WDT(); //FASTCPU + disableCore1WDT(); //SLOWCPU + + hal.console->printf("%s:%d running with CONFIG_FREERTOS_HZ=%d\n", __PRETTY_FUNCTION__, __LINE__,CONFIG_FREERTOS_HZ); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #define FASTCPU 0 + #define SLOWCPU 1 + // pin main thread to Core 0, and we'll also pin other heavy-tasks to core 1, like wifi-related. - if (xTaskCreatePinnedToCore(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle,1) != pdPASS) { + if (xTaskCreatePinnedToCore(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle,FASTCPU) != pdPASS) { //if (xTaskCreate(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _main_thread\n"); + hal.console->printf("FAILED to create task _main_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _main_thread\n"); + hal.console->printf("OK created task _main_thread on FASTCPU\n"); } - if (xTaskCreate(_timer_thread, "APM_TIMER", TIMER_SS, this, TIMER_PRIO, &_timer_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _timer_thread\n"); + if (xTaskCreatePinnedToCore(_timer_thread, "APM_TIMER", TIMER_SS, this, TIMER_PRIO, &_timer_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _timer_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _timer_thread\n"); + hal.console->printf("OK created task _timer_thread on FASTCPU\n"); } - if (xTaskCreatePinnedToCore(_rcout_thread, "APM_RCOUT", RCOUT_SS, this, RCOUT_PRIO, &_rcout_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _rcout_thread\n"); + if (xTaskCreatePinnedToCore(_rcout_thread, "APM_RCOUT", RCOUT_SS, this, RCOUT_PRIO, &_rcout_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _rcout_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _rcout_thread\n"); + hal.console->printf("OK created task _rcout_thread on SLOWCPU\n"); } - if (xTaskCreatePinnedToCore(_rcin_thread, "APM_RCIN", RCIN_SS, this, RCIN_PRIO, &_rcin_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _rcin_thread\n"); + if (xTaskCreatePinnedToCore(_rcin_thread, "APM_RCIN", RCIN_SS, this, RCIN_PRIO, &_rcin_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _rcin_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _rcin_thread\n"); + hal.console->printf("OK created task _rcin_thread on SLOWCPU\n"); } - // pin this thread to Core 1 - if (xTaskCreatePinnedToCore(_uart_thread, "APM_UART", UART_SS, this, UART_PRIO, &_uart_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _uart_thread\n"); + // pin this thread to Core 1 as it keeps all teh uart/s feed data, and we need that quick. + if (xTaskCreatePinnedToCore(_uart_thread, "APM_UART", UART_SS, this, UART_PRIO, &_uart_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _uart_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _uart_thread\n"); + hal.console->printf("OK created task _uart_thread on FASTCPU\n"); } - if (xTaskCreate(_io_thread, "SchedulerIO:APM_IO", IO_SS, this, IO_PRIO, &_io_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _io_thread\n"); + // we put thos on the SLOW core as it mounts the sd card, and that often isn't conencted. + if (xTaskCreatePinnedToCore(_io_thread, "SchedulerIO:APM_IO", IO_SS, this, IO_PRIO, &_io_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _io_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _io_thread\n"); + hal.console->printf("OK created task _io_thread on SLOWCPU\n"); } - if (xTaskCreate(_storage_thread, "APM_STORAGE", STORAGE_SS, this, STORAGE_PRIO, &_storage_task_handle) != pdPASS) { //no actual flash writes without this, storage kinda appears to work, but does an erase on every boot and params don't persist over reset etc. + if (xTaskCreatePinnedToCore(_storage_thread, "APM_STORAGE", STORAGE_SS, this, STORAGE_PRIO, &_storage_task_handle,SLOWCPU) != pdPASS) { //no actual flash writes without this, storage kinda appears to work, but does an erase on every boot and params don't persist over reset etc. hal.console->printf("FAILED to create task _storage_thread\n"); } else { hal.console->printf("OK created task _storage_thread\n"); } - // xTaskCreate(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr); + // xTaskCreatePinnedToCore(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr,SLOWCPU); - //disableCore0WDT(); - //disableCore1WDT(); + hal.console->printf("OK Sched Init, enabling WD\n"); + enableCore0WDT(); //FASTCPU + //enableCore1WDT(); //we don't enable WD on SLOWCPU right now. } @@ -209,6 +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); } } @@ -441,7 +468,7 @@ void Scheduler::_storage_thread(void* arg) printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; - while (!_initialized) { + while (!sched->_initialized) { sched->delay_microseconds(10000); } #ifdef SCHEDDEBUG @@ -475,7 +502,7 @@ void Scheduler::_uart_thread(void *arg) printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; - while (!_initialized) { + while (!sched->_initialized) { sched->delay_microseconds(2000); } #ifdef SCHEDDEBUG diff --git a/libraries/AP_HAL_ESP32/SdCard.cpp b/libraries/AP_HAL_ESP32/SdCard.cpp index f652e865fd..725235fba9 100644 --- a/libraries/AP_HAL_ESP32/SdCard.cpp +++ b/libraries/AP_HAL_ESP32/SdCard.cpp @@ -32,6 +32,8 @@ #include #include "SPIDevice.h" +#include "soc/rtc_wdt.h" + #ifdef HAL_ESP32_SDCARD #if CONFIG_IDF_TARGET_ESP32S2 ||CONFIG_IDF_TARGET_ESP32C3 @@ -163,8 +165,9 @@ 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); @@ -234,7 +237,9 @@ 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/WiFiDriver.cpp b/libraries/AP_HAL_ESP32/WiFiDriver.cpp index b11c6b978c..43c9135e15 100644 --- a/libraries/AP_HAL_ESP32/WiFiDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiDriver.cpp @@ -50,10 +50,15 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) if (_state == NOT_INITIALIZED) { initialize_wifi(); - if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread\n"); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #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"); } else { - hal.console->printf("OK created task _wifi_thread\n"); + hal.console->printf("OK created task _wifi_thread on FASTCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index 6e08cabfb2..eb2fbdbec2 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -32,6 +32,8 @@ #include "lwip/sys.h" #include "lwip/netdb.h" +#include "soc/rtc_wdt.h" + using namespace ESP32; extern const AP_HAL::HAL& hal; @@ -52,10 +54,15 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) return; } - if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread2\n"); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #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"); } else { - hal.console->printf("OK created task _wifi_thread2\n"); + hal.console->printf("OK created task _wifi_thread2 on FASTCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); @@ -219,9 +226,10 @@ 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(); diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig index cbdbc78de6..725b24a4a3 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig @@ -203,6 +203,7 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y # CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set # CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID is not set # CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT is not set +# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set # end of TWAI configuration # @@ -247,9 +248,16 @@ CONFIG_EFUSE_MAX_BLK_LEN=192 # CONFIG_ESP32_REV_MIN_0=y # CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_1_1 is not set # CONFIG_ESP32_REV_MIN_2 is not set # CONFIG_ESP32_REV_MIN_3 is not set +# CONFIG_ESP32_REV_MIN_3_1 is not set CONFIG_ESP32_REV_MIN=0 +CONFIG_ESP32_REV_MIN_FULL=0 +CONFIG_ESP_REV_MIN_FULL=0 +CONFIG_ESP32_REV_MAX_FULL_STR_OPT=y +CONFIG_ESP32_REV_MAX_FULL=399 +CONFIG_ESP_REV_MAX_FULL=399 CONFIG_ESP32_DPORT_WORKAROUND=y # CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set # CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set @@ -351,6 +359,7 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y # CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 +# CONFIG_ESP_MAC_IGNORE_MAC_CRC_ERROR is not set # end of MAC Config # @@ -360,6 +369,8 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y +# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set +CONFIG_ESP_SLEEP_GPIO_ENABLE_INTERNAL_RESISTORS=y # end of Sleep Config # @@ -393,6 +404,10 @@ CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP_PHY_MAX_TX_POWER=20 CONFIG_ESP_PHY_REDUCE_TX_POWER=y +CONFIG_ESP_PHY_RF_CAL_PARTIAL=y +# CONFIG_ESP_PHY_RF_CAL_NONE is not set +# CONFIG_ESP_PHY_RF_CAL_FULL is not set +CONFIG_ESP_PHY_CALIBRATION_MODE=0 # end of PHY # @@ -404,6 +419,13 @@ CONFIG_PM_ENABLE=y # CONFIG_PM_TRACE is not set # end of Power Management +# +# ESP Ringbuf +# +# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set +# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set +# end of ESP Ringbuf + # # ESP System Settings # @@ -470,6 +492,10 @@ CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=16 CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=16 +CONFIG_ESP_WIFI_STATIC_RX_MGMT_BUFFER=y +# CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUFFER is not set +CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUF=0 +CONFIG_ESP_WIFI_RX_MGMT_BUF_NUM_DEF=5 # CONFIG_ESP32_WIFI_CSI_ENABLED is not set # CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED is not set # CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED is not set @@ -485,6 +511,8 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y # CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set # CONFIG_ESP_WIFI_GMAC_SUPPORT is not set CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y +# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set +CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 # end of Wi-Fi # @@ -498,8 +526,10 @@ CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y # CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set CONFIG_ESP_COREDUMP_ENABLE=y +CONFIG_ESP_COREDUMP_LOGS=y CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 CONFIG_ESP_COREDUMP_UART_DELAY=0 +CONFIG_ESP_COREDUMP_STACK_SIZE=0 CONFIG_ESP_COREDUMP_DECODE_INFO=y # CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set CONFIG_ESP_COREDUMP_DECODE="info" @@ -632,7 +662,9 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y # CONFIG_LWIP_LOCAL_HOSTNAME="espressif" # CONFIG_LWIP_NETIF_API is not set +CONFIG_LWIP_TCPIP_TASK_PRIO=18 # CONFIG_LWIP_TCPIP_CORE_LOCKING is not set +# CONFIG_LWIP_CHECK_THREAD_SAFETY is not set CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y # CONFIG_LWIP_L2_TO_L3_COPY is not set # CONFIG_LWIP_IRAM_OPTIMIZATION is not set @@ -653,12 +685,15 @@ CONFIG_LWIP_IP6_FRAG=y # CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set CONFIG_LWIP_ESP_GRATUITOUS_ARP=y CONFIG_LWIP_GARP_TMR_INTERVAL=60 +CONFIG_LWIP_ESP_MLDV6_REPORT=y +CONFIG_LWIP_MLDV6_TMR_INTERVAL=40 CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y # CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y # CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set CONFIG_LWIP_DHCP_OPTIONS_LEN=68 +CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1 # # DHCP server @@ -688,10 +723,13 @@ CONFIG_LWIP_TCP_SYNMAXRTX=6 CONFIG_LWIP_TCP_MSS=1436 CONFIG_LWIP_TCP_TMR_INTERVAL=250 CONFIG_LWIP_TCP_MSL=60000 +CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 CONFIG_LWIP_TCP_WND_DEFAULT=5744 CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 CONFIG_LWIP_TCP_QUEUE_OOSEQ=y +CONFIG_LWIP_TCP_OOSEQ_TIMEOUT=6 +CONFIG_LWIP_TCP_OOSEQ_MAX_PBUFS=4 # CONFIG_LWIP_TCP_SACK_OUT is not set # CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set CONFIG_LWIP_TCP_OVERSIZE_MSS=y @@ -803,6 +841,7 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set # CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set +CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 # end of Certificate Bundle # CONFIG_MBEDTLS_ECP_RESTARTABLE is not set @@ -921,6 +960,7 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # # NVS # +# CONFIG_NVS_ASSERT_ERROR_CHECK is not set # end of NVS # @@ -989,7 +1029,6 @@ CONFIG_VFS_SUPPORT_TERMIOS=y # Host File System I/O (Semihosting) # CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # end of Host File System I/O (Semihosting) # end of Virtual file system @@ -1131,6 +1170,7 @@ CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y CONFIG_ESP32_ENABLE_COREDUMP=y CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 +CONFIG_ESP32_CORE_DUMP_STACK_SIZE=0 CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y # CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set CONFIG_ESP32_CORE_DUMP_DECODE="info" @@ -1176,5 +1216,4 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y CONFIG_SUPPORT_TERMIOS=y CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # End of deprecated options