mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: improve the reported LOOP_RATE on esp32s3 to similar loop rate to classic esp32
getting a loop rate of around 130 on both now source modules/esp_idf/export.sh ./waf configure --board=esp32s3empty --debug ./waf copter cd build/esp32buzz/esp-idf_build/ ninja menuconfig ./waf configure --board=esp32buzz --debug ./waf copter cd build/esp32buzz/esp-idf_build/ ninja menuconfig and try to get both the resulting modified sdkconfig as smiilar as possible - this causes s3 to use qio, which is faster, and also puts the wifi stuff onto CORE1 on both configs. s3: loop_rate: actual: 148.097137Hz, expected: 400Hz loop_rate: actual: 147.908691Hz, expected: 400Hz classic: loop_rate: actual: 188.718842Hz, expected: 400Hz loop_rate: actual: 191.819748Hz, expected: 400Hz
This commit is contained in:
parent
8856100e39
commit
61e83dcd0e
|
@ -153,7 +153,7 @@ void executor(T oui)
|
|||
oui();
|
||||
}
|
||||
|
||||
void Scheduler::thread_create_trampoline(void *ctx)
|
||||
void IRAM_ATTR Scheduler::thread_create_trampoline(void *ctx)
|
||||
{
|
||||
AP_HAL::MemberProc *t = (AP_HAL::MemberProc *)ctx;
|
||||
(*t)();
|
||||
|
@ -216,7 +216,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
|||
return true;
|
||||
}
|
||||
|
||||
void Scheduler::delay(uint16_t ms)
|
||||
void IRAM_ATTR Scheduler::delay(uint16_t ms)
|
||||
{
|
||||
uint64_t start = AP_HAL::micros64();
|
||||
while ((AP_HAL::micros64() - start)/1000 < ms) {
|
||||
|
@ -229,7 +229,7 @@ void Scheduler::delay(uint16_t ms)
|
|||
}
|
||||
}
|
||||
|
||||
void Scheduler::delay_microseconds(uint16_t us)
|
||||
void IRAM_ATTR Scheduler::delay_microseconds(uint16_t us)
|
||||
{
|
||||
if (in_main_thread() && us < 100) {
|
||||
ets_delay_us(us);
|
||||
|
@ -240,7 +240,7 @@ void Scheduler::delay_microseconds(uint16_t us)
|
|||
}
|
||||
}
|
||||
|
||||
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
void IRAM_ATTR Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
#ifdef SCHEDDEBUG
|
||||
printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -260,7 +260,7 @@ void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
|||
_timer_sem.give();
|
||||
}
|
||||
|
||||
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
void IRAM_ATTR Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
||||
{
|
||||
#ifdef SCHEDDEBUG
|
||||
printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -281,7 +281,7 @@ void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
|||
_io_sem.give();
|
||||
}
|
||||
|
||||
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||
void IRAM_ATTR Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
||||
{
|
||||
_failsafe = failsafe;
|
||||
}
|
||||
|
@ -294,7 +294,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
|||
esp_restart();
|
||||
}
|
||||
|
||||
bool Scheduler::in_main_thread() const
|
||||
bool IRAM_ATTR Scheduler::in_main_thread() const
|
||||
{
|
||||
return _main_task_handle == xTaskGetCurrentTaskHandle();
|
||||
}
|
||||
|
@ -316,7 +316,7 @@ bool Scheduler::is_system_initialized()
|
|||
return _initialized;
|
||||
}
|
||||
|
||||
void Scheduler::_timer_thread(void *arg)
|
||||
void IRAM_ATTR Scheduler::_timer_thread(void *arg)
|
||||
{
|
||||
#ifdef SCHEDDEBUG
|
||||
printf("%s:%d start\n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -343,7 +343,7 @@ void Scheduler::_timer_thread(void *arg)
|
|||
}
|
||||
}
|
||||
|
||||
void Scheduler::_rcout_thread(void* arg)
|
||||
void IRAM_ATTR Scheduler::_rcout_thread(void* arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
while (!_initialized) {
|
||||
|
@ -357,7 +357,7 @@ void Scheduler::_rcout_thread(void* arg)
|
|||
}
|
||||
}
|
||||
|
||||
void Scheduler::_run_timers()
|
||||
void IRAM_ATTR Scheduler::_run_timers()
|
||||
{
|
||||
#ifdef SCHEDULERDEBUG
|
||||
printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -391,7 +391,7 @@ void Scheduler::_run_timers()
|
|||
_in_timer_proc = false;
|
||||
}
|
||||
|
||||
void Scheduler::_rcin_thread(void *arg)
|
||||
void IRAM_ATTR Scheduler::_rcin_thread(void *arg)
|
||||
{
|
||||
Scheduler *sched = (Scheduler *)arg;
|
||||
while (!_initialized) {
|
||||
|
@ -404,7 +404,7 @@ void Scheduler::_rcin_thread(void *arg)
|
|||
}
|
||||
}
|
||||
|
||||
void Scheduler::_run_io(void)
|
||||
void IRAM_ATTR Scheduler::_run_io(void)
|
||||
{
|
||||
#ifdef SCHEDULERDEBUG
|
||||
printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -430,7 +430,7 @@ void Scheduler::_run_io(void)
|
|||
_in_io_proc = false;
|
||||
}
|
||||
|
||||
void Scheduler::_io_thread(void* arg)
|
||||
void IRAM_ATTR Scheduler::_io_thread(void* arg)
|
||||
{
|
||||
#ifdef SCHEDDEBUG
|
||||
printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -496,7 +496,7 @@ void Scheduler::_print_profile(void* arg)
|
|||
|
||||
}
|
||||
|
||||
void Scheduler::_uart_thread(void *arg)
|
||||
void IRAM_ATTR Scheduler::_uart_thread(void *arg)
|
||||
{
|
||||
#ifdef SCHEDDEBUG
|
||||
printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__);
|
||||
|
@ -519,7 +519,7 @@ void Scheduler::_uart_thread(void *arg)
|
|||
|
||||
|
||||
// get the active main loop rate
|
||||
uint16_t Scheduler::get_loop_rate_hz(void)
|
||||
uint16_t IRAM_ATTR Scheduler::get_loop_rate_hz(void)
|
||||
{
|
||||
if (_active_loop_rate_hz == 0) {
|
||||
_active_loop_rate_hz = _loop_rate_hz;
|
||||
|
|
|
@ -69,15 +69,18 @@ public:
|
|||
static const int IO_PRIO = 6;
|
||||
static const int STORAGE_PRIO = 6; */
|
||||
|
||||
// configMAX_PRIORITIES=25
|
||||
|
||||
|
||||
static const int SPI_PRIORITY = 24; // if your primary imu is spi, this should be above the i2c value, spi is better.
|
||||
static const int MAIN_PRIO = 24; // cpu0: we want scheduler running at full tilt.
|
||||
static const int I2C_PRIORITY = 5; // if your primary imu is i2c, this should be above the spi value, i2c is not preferred.
|
||||
static const int TIMER_PRIO = 22; // a low priority mere might cause wifi thruput to suffer
|
||||
static const int RCIN_PRIO = 15;
|
||||
static const int TIMER_PRIO = 23; //dont make 24. a low priority mere might cause wifi thruput to suffer
|
||||
static const int RCIN_PRIO = 5;
|
||||
static const int RCOUT_PRIO = 10;
|
||||
static const int WIFI_PRIO1 = 20; //cpu1:
|
||||
static const int WIFI_PRIO2 = 12; //cpu1:
|
||||
static const int UART_PRIO = 24; //cpu1: a low priority mere might cause wifi thruput to suffer, as wifi gets passed its data frim the uart subsustem in _writebuf/_readbuf
|
||||
static const int UART_PRIO = 23; //dont make 24, scheduler suffers a bit. cpu1: a low priority mere might cause wifi thruput to suffer, as wifi gets passed its data frim the uart subsustem in _writebuf/_readbuf
|
||||
static const int IO_PRIO = 5;
|
||||
static const int STORAGE_PRIO = 4;
|
||||
|
||||
|
|
|
@ -56,9 +56,7 @@ CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y
|
|||
# CONFIG_BOOTLOADER_FACTORY_RESET is not set
|
||||
# CONFIG_BOOTLOADER_APP_TEST is not set
|
||||
CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y
|
||||
CONFIG_BOOTLOADER_WDT_ENABLE=n
|
||||
# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set
|
||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||
# CONFIG_BOOTLOADER_WDT_ENABLE is not set
|
||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set
|
||||
|
@ -318,19 +316,8 @@ CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
|||
#
|
||||
# Ethernet
|
||||
#
|
||||
CONFIG_ETH_ENABLED=y
|
||||
CONFIG_ETH_USE_ESP32_EMAC=y
|
||||
CONFIG_ETH_PHY_INTERFACE_RMII=y
|
||||
CONFIG_ETH_RMII_CLK_INPUT=y
|
||||
# CONFIG_ETH_RMII_CLK_OUTPUT is not set
|
||||
CONFIG_ETH_RMII_CLK_IN_GPIO=0
|
||||
CONFIG_ETH_DMA_BUFFER_SIZE=512
|
||||
CONFIG_ETH_DMA_RX_BUFFER_NUM=10
|
||||
CONFIG_ETH_DMA_TX_BUFFER_NUM=10
|
||||
CONFIG_ETH_USE_SPI_ETHERNET=y
|
||||
CONFIG_ETH_SPI_ETHERNET_DM9051=y
|
||||
# CONFIG_ETH_SPI_ETHERNET_W5500 is not set
|
||||
# CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set
|
||||
# CONFIG_ETH_USE_ESP32_EMAC is not set
|
||||
# CONFIG_ETH_USE_SPI_ETHERNET is not set
|
||||
# CONFIG_ETH_USE_OPENETH is not set
|
||||
# end of Ethernet
|
||||
|
||||
|
@ -455,14 +442,8 @@ CONFIG_ESP_CONSOLE_UART=y
|
|||
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_ESP_INT_WDT=n
|
||||
CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000
|
||||
CONFIG_ESP_INT_WDT_CHECK_CPU1=y
|
||||
CONFIG_ESP_TASK_WDT=n
|
||||
# CONFIG_ESP_TASK_WDT_PANIC is not set
|
||||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU1=y
|
||||
# CONFIG_ESP_INT_WDT is not set
|
||||
# CONFIG_ESP_TASK_WDT is not set
|
||||
# CONFIG_ESP_PANIC_HANDLER_IRAM is not set
|
||||
# CONFIG_ESP_DEBUG_STUBS_ENABLE is not set
|
||||
# CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_5 is not set
|
||||
|
@ -497,11 +478,13 @@ CONFIG_ESP_WIFI_STATIC_RX_MGMT_BUFFER=y
|
|||
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
|
||||
# CONFIG_ESP32_WIFI_NVS_ENABLED is not set
|
||||
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y
|
||||
# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set
|
||||
CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_TX_BA_WIN=6
|
||||
CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_RX_BA_WIN=4
|
||||
CONFIG_ESP32_WIFI_NVS_ENABLED=y
|
||||
# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0 is not set
|
||||
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1=y
|
||||
CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752
|
||||
CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32
|
||||
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
||||
|
@ -754,10 +737,10 @@ CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y
|
|||
# end of Checksums
|
||||
|
||||
CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x1
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
|
@ -1150,14 +1133,8 @@ CONFIG_CONSOLE_UART_DEFAULT=y
|
|||
CONFIG_CONSOLE_UART=y
|
||||
CONFIG_CONSOLE_UART_NUM=0
|
||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_INT_WDT=n
|
||||
CONFIG_INT_WDT_TIMEOUT_MS=1000
|
||||
CONFIG_INT_WDT_CHECK_CPU1=y
|
||||
CONFIG_TASK_WDT=n
|
||||
# CONFIG_TASK_WDT_PANIC is not set
|
||||
CONFIG_TASK_WDT_TIMEOUT_S=5
|
||||
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y
|
||||
# CONFIG_INT_WDT is not set
|
||||
# CONFIG_TASK_WDT is not set
|
||||
# CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set
|
||||
CONFIG_TIMER_TASK_STACK_SIZE=3584
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set
|
||||
|
@ -1197,10 +1174,10 @@ CONFIG_TCP_OVERSIZE_MSS=y
|
|||
# CONFIG_TCP_OVERSIZE_DISABLE is not set
|
||||
CONFIG_UDP_RECVMBOX_SIZE=6
|
||||
CONFIG_TCPIP_TASK_STACK_SIZE=3072
|
||||
CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_TCPIP_TASK_AFFINITY_CPU1=y
|
||||
CONFIG_TCPIP_TASK_AFFINITY=0x1
|
||||
# CONFIG_PPP_SUPPORT is not set
|
||||
CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5
|
||||
CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072
|
||||
|
|
|
@ -89,9 +89,9 @@ CONFIG_BOOT_ROM_LOG_ALWAYS_ON=y
|
|||
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
||||
# CONFIG_ESPTOOLPY_NO_STUB is not set
|
||||
# CONFIG_ESPTOOLPY_OCT_FLASH is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set
|
||||
CONFIG_ESPTOOLPY_FLASHMODE_QIO=y
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set
|
||||
CONFIG_ESPTOOLPY_FLASHMODE_DIO=y
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_DIO is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set
|
||||
CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y
|
||||
CONFIG_ESPTOOLPY_FLASHMODE="dio"
|
||||
|
@ -320,11 +320,7 @@ CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
|||
#
|
||||
# Ethernet
|
||||
#
|
||||
CONFIG_ETH_ENABLED=y
|
||||
CONFIG_ETH_USE_SPI_ETHERNET=y
|
||||
# CONFIG_ETH_SPI_ETHERNET_DM9051 is not set
|
||||
# CONFIG_ETH_SPI_ETHERNET_W5500 is not set
|
||||
# CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set
|
||||
# CONFIG_ETH_USE_SPI_ETHERNET is not set
|
||||
# CONFIG_ETH_USE_OPENETH is not set
|
||||
# end of Ethernet
|
||||
|
||||
|
@ -493,8 +489,8 @@ CONFIG_ESP32_WIFI_TX_BA_WIN=6
|
|||
CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_RX_BA_WIN=6
|
||||
CONFIG_ESP32_WIFI_NVS_ENABLED=y
|
||||
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y
|
||||
# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set
|
||||
# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0 is not set
|
||||
CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1=y
|
||||
CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752
|
||||
CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32
|
||||
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
||||
|
@ -570,8 +566,8 @@ CONFIG_FATFS_PER_FILE_CACHE=y
|
|||
# CONFIG_FREERTOS_UNICORE is not set
|
||||
CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_FREERTOS_TICK_SUPPORT_SYSTIMER=y
|
||||
CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1=y
|
||||
# CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3 is not set
|
||||
# CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1 is not set
|
||||
CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3=y
|
||||
CONFIG_FREERTOS_SYSTICK_USES_SYSTIMER=y
|
||||
CONFIG_FREERTOS_HZ=1000
|
||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||
|
@ -580,9 +576,9 @@ CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
|||
CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y
|
||||
# CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK is not set
|
||||
CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y
|
||||
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1
|
||||
CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y
|
||||
# CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE is not set
|
||||
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10
|
||||
# CONFIG_FREERTOS_ASSERT_FAIL_ABORT is not set
|
||||
CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE=y
|
||||
# CONFIG_FREERTOS_ASSERT_DISABLE is not set
|
||||
CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536
|
||||
CONFIG_FREERTOS_ISR_STACKSIZE=2100
|
||||
|
@ -660,7 +656,7 @@ CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y
|
|||
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
||||
# CONFIG_LWIP_IRAM_OPTIMIZATION is not set
|
||||
CONFIG_LWIP_TIMERS_ONDEMAND=y
|
||||
CONFIG_LWIP_MAX_SOCKETS=10
|
||||
CONFIG_LWIP_MAX_SOCKETS=5
|
||||
# CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set
|
||||
# CONFIG_LWIP_SO_LINGER is not set
|
||||
CONFIG_LWIP_SO_REUSE=y
|
||||
|
@ -745,10 +741,10 @@ CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y
|
|||
# end of Checksums
|
||||
|
||||
CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=3072
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x1
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
|
@ -1058,9 +1054,9 @@ CONFIG_LOG_BOOTLOADER_LEVEL_ERROR=y
|
|||
CONFIG_LOG_BOOTLOADER_LEVEL=1
|
||||
# CONFIG_APP_ROLLBACK_ENABLE is not set
|
||||
# CONFIG_FLASH_ENCRYPTION_ENABLED is not set
|
||||
# CONFIG_FLASHMODE_QIO is not set
|
||||
CONFIG_FLASHMODE_QIO=y
|
||||
# CONFIG_FLASHMODE_QOUT is not set
|
||||
CONFIG_FLASHMODE_DIO=y
|
||||
# CONFIG_FLASHMODE_DIO is not set
|
||||
# CONFIG_FLASHMODE_DOUT is not set
|
||||
# CONFIG_MONITOR_BAUD_9600B is not set
|
||||
# CONFIG_MONITOR_BAUD_57600B is not set
|
||||
|
@ -1154,10 +1150,10 @@ CONFIG_TCP_OVERSIZE_MSS=y
|
|||
# CONFIG_TCP_OVERSIZE_DISABLE is not set
|
||||
CONFIG_UDP_RECVMBOX_SIZE=6
|
||||
CONFIG_TCPIP_TASK_STACK_SIZE=3072
|
||||
CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
# CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set
|
||||
CONFIG_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_TCPIP_TASK_AFFINITY_CPU1=y
|
||||
CONFIG_TCPIP_TASK_AFFINITY=0x1
|
||||
# CONFIG_PPP_SUPPORT is not set
|
||||
CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5
|
||||
CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=3072
|
||||
|
|
Loading…
Reference in New Issue