mirror of https://github.com/ArduPilot/ardupilot
HAL_ESP32: added esp32s3empty target
This commit is contained in:
parent
6fb99d6b1e
commit
e2f82ed9bc
|
@ -33,6 +33,7 @@
|
||||||
#include "esp_log.h"
|
#include "esp_log.h"
|
||||||
#include "esp_system.h"
|
#include "esp_system.h"
|
||||||
#include "esp_heap_caps.h"
|
#include "esp_heap_caps.h"
|
||||||
|
#include <AP_Common/ExpandingString.h>
|
||||||
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
@ -268,28 +269,17 @@ bool Util::was_watchdog_reset() const
|
||||||
|| reason == ESP_RST_WDT;
|
|| reason == ESP_RST_WDT;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
||||||
/*
|
/*
|
||||||
display stack usage as text buffer for @SYS/threads.txt
|
display stack usage as text buffer for @SYS/threads.txt
|
||||||
*/
|
*/
|
||||||
size_t Util::thread_info(char *buf, size_t bufsize)
|
void Util::thread_info(ExpandingString &str)
|
||||||
{
|
{
|
||||||
thread_t *tp;
|
|
||||||
size_t total = 0;
|
|
||||||
|
|
||||||
// a header to allow for machine parsers to determine format
|
// a header to allow for machine parsers to determine format
|
||||||
int n = snprintf(buf, bufsize, "ThreadsV1\n");
|
str.printf("ThreadsV1\n");
|
||||||
if (n <= 0) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
// char buffer[1024];
|
// char buffer[1024];
|
||||||
// vTaskGetRunTimeStats(buffer);
|
// vTaskGetRunTimeStats(buffer);
|
||||||
// snprintf(buf, bufsize,"\n\n%s\n", buffer);
|
// snprintf(buf, bufsize,"\n\n%s\n", buffer);
|
||||||
|
|
||||||
// total = ..
|
|
||||||
|
|
||||||
return total;
|
|
||||||
}
|
}
|
||||||
#endif // CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
||||||
|
|
||||||
|
|
|
@ -62,10 +62,8 @@ public:
|
||||||
// return true if the reason for the reboot was a watchdog reset
|
// return true if the reason for the reboot was a watchdog reset
|
||||||
bool was_watchdog_reset() const override;
|
bool was_watchdog_reset() const override;
|
||||||
|
|
||||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
||||||
// request information on running threads
|
// request information on running threads
|
||||||
size_t thread_info(char *buf, size_t bufsize) override;
|
void thread_info(ExpandingString &str) override;
|
||||||
#endif
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#ifdef HAL_PWM_ALARM
|
#ifdef HAL_PWM_ALARM
|
||||||
|
|
|
@ -0,0 +1,89 @@
|
||||||
|
/*
|
||||||
|
* This file is free software: you can redistribute it and/or modify it
|
||||||
|
* under the terms of the GNU General Public License as published by the
|
||||||
|
* Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This file is distributed in the hope that it will be useful, but
|
||||||
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License along
|
||||||
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_ESP32_S3EMPTY
|
||||||
|
// make sensor selection clearer
|
||||||
|
|
||||||
|
//- these are missing from esp-idf......will not be needed later
|
||||||
|
#define RTC_WDT_STG_SEL_OFF 0
|
||||||
|
#define RTC_WDT_STG_SEL_INT 1
|
||||||
|
#define RTC_WDT_STG_SEL_RESET_CPU 2
|
||||||
|
#define RTC_WDT_STG_SEL_RESET_SYSTEM 3
|
||||||
|
#define RTC_WDT_STG_SEL_RESET_RTC 4
|
||||||
|
|
||||||
|
#define HAL_ESP32_BOARD_NAME "esp32s3empty"
|
||||||
|
|
||||||
|
#define HAL_ESP32_RMT_RX_PIN_NUMBER GPIO_NUM_14
|
||||||
|
|
||||||
|
// no sensors
|
||||||
|
#define HAL_INS_DEFAULT HAL_INS_NONE
|
||||||
|
|
||||||
|
#define HAL_BARO_ALLOW_INIT_NO_BARO 1
|
||||||
|
|
||||||
|
#define AP_COMPASS_ENABLE_DEFAULT 0
|
||||||
|
#define ALLOW_ARM_NO_COMPASS
|
||||||
|
#define AP_AIRSPEED_ENABLED 0
|
||||||
|
#define AP_AIRSPEED_ANALOG_ENABLED 0
|
||||||
|
#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
|
||||||
|
// no ADC
|
||||||
|
#define HAL_DISABLE_ADC_DRIVER 1
|
||||||
|
#define HAL_USE_ADC 0
|
||||||
|
|
||||||
|
// 2 use udp, 1 use tcp... for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550
|
||||||
|
#define HAL_ESP32_WIFI 1
|
||||||
|
|
||||||
|
// see boards.py
|
||||||
|
#ifndef ENABLE_HEAP
|
||||||
|
#define ENABLE_HEAP 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define WIFI_SSID "ardupilot123"
|
||||||
|
#define WIFI_PWD "ardupilot123"
|
||||||
|
|
||||||
|
//RCOUT which pins are used?
|
||||||
|
|
||||||
|
#define HAL_ESP32_RCOUT { GPIO_NUM_11,GPIO_NUM_10, GPIO_NUM_9, GPIO_NUM_8, GPIO_NUM_7, GPIO_NUM_6 }
|
||||||
|
|
||||||
|
// SPI BUS setup, including gpio, dma, etc
|
||||||
|
// note... we use 'vspi' for the bmp280 and mpu9250
|
||||||
|
#define HAL_ESP32_SPI_BUSES {}
|
||||||
|
|
||||||
|
// SPI per-device setup, including speeds, etc.
|
||||||
|
#define HAL_ESP32_SPI_DEVICES {}
|
||||||
|
|
||||||
|
//I2C bus list
|
||||||
|
#define HAL_ESP32_I2C_BUSES {.port=I2C_NUM_0, .sda=GPIO_NUM_13, .scl=GPIO_NUM_14, .speed=400*KHZ, .internal=true, .soft=true}
|
||||||
|
|
||||||
|
// rcin on what pin?
|
||||||
|
#define HAL_ESP32_RCIN GPIO_NUM_14
|
||||||
|
|
||||||
|
|
||||||
|
//HARDWARE UARTS
|
||||||
|
#define HAL_ESP32_UART_DEVICES \
|
||||||
|
{.port=UART_NUM_0, .rx=GPIO_NUM_44, .tx=GPIO_NUM_43 },{.port=UART_NUM_1, .rx=GPIO_NUM_17, .tx=GPIO_NUM_18 }
|
||||||
|
|
||||||
|
#define HAL_LOGGING_FILESYSTEM_ENABLED 0
|
||||||
|
#define HAL_LOGGING_DATAFLASH_ENABLED 0
|
||||||
|
#define HAL_LOGGING_MAVLINK_ENABLED 0
|
||||||
|
|
||||||
|
#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS"
|
||||||
|
#define HAL_BOARD_STORAGE_DIRECTORY "/SDCARD/APM/STORAGE"
|
||||||
|
#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS"
|
||||||
|
#define HAL_BOARD_TERRAIN_DIRECTORY "/SDCARD/APM/TERRAIN"
|
||||||
|
|
||||||
|
#define HAL_LOGGING_BACKENDS_DEFAULT 1
|
||||||
|
|
|
@ -203,7 +203,6 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||||
# CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set
|
# 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_FRAME_INVALID is not set
|
||||||
# CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT 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
|
# end of TWAI configuration
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -248,16 +247,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||||
#
|
#
|
||||||
CONFIG_ESP32_REV_MIN_0=y
|
CONFIG_ESP32_REV_MIN_0=y
|
||||||
# CONFIG_ESP32_REV_MIN_1 is not set
|
# 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_2 is not set
|
||||||
# CONFIG_ESP32_REV_MIN_3 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=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_DPORT_WORKAROUND=y
|
||||||
# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set
|
# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set
|
||||||
# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set
|
# CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set
|
||||||
|
@ -359,7 +351,6 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y
|
||||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y
|
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y
|
||||||
# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set
|
# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set
|
||||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2
|
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2
|
||||||
# CONFIG_ESP_MAC_IGNORE_MAC_CRC_ERROR is not set
|
|
||||||
# end of MAC Config
|
# end of MAC Config
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -369,7 +360,6 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2
|
||||||
CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y
|
CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y
|
||||||
# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set
|
# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set
|
||||||
CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y
|
CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y
|
||||||
# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set
|
|
||||||
# end of Sleep Config
|
# end of Sleep Config
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -414,13 +404,6 @@ CONFIG_PM_ENABLE=y
|
||||||
# CONFIG_PM_TRACE is not set
|
# CONFIG_PM_TRACE is not set
|
||||||
# end of Power Management
|
# 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
|
# ESP System Settings
|
||||||
#
|
#
|
||||||
|
@ -502,8 +485,6 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y
|
||||||
# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set
|
# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set
|
||||||
# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set
|
# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set
|
||||||
CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y
|
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
|
# end of Wi-Fi
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -519,7 +500,6 @@ CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y
|
||||||
CONFIG_ESP_COREDUMP_ENABLE=y
|
CONFIG_ESP_COREDUMP_ENABLE=y
|
||||||
CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64
|
CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64
|
||||||
CONFIG_ESP_COREDUMP_UART_DELAY=0
|
CONFIG_ESP_COREDUMP_UART_DELAY=0
|
||||||
CONFIG_ESP_COREDUMP_STACK_SIZE=0
|
|
||||||
CONFIG_ESP_COREDUMP_DECODE_INFO=y
|
CONFIG_ESP_COREDUMP_DECODE_INFO=y
|
||||||
# CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set
|
# CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set
|
||||||
CONFIG_ESP_COREDUMP_DECODE="info"
|
CONFIG_ESP_COREDUMP_DECODE="info"
|
||||||
|
@ -653,7 +633,6 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y
|
||||||
CONFIG_LWIP_LOCAL_HOSTNAME="espressif"
|
CONFIG_LWIP_LOCAL_HOSTNAME="espressif"
|
||||||
# CONFIG_LWIP_NETIF_API is not set
|
# CONFIG_LWIP_NETIF_API is not set
|
||||||
# CONFIG_LWIP_TCPIP_CORE_LOCKING is not set
|
# 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_DNS_SUPPORT_MDNS_QUERIES=y
|
||||||
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
||||||
# CONFIG_LWIP_IRAM_OPTIMIZATION is not set
|
# CONFIG_LWIP_IRAM_OPTIMIZATION is not set
|
||||||
|
@ -674,15 +653,12 @@ CONFIG_LWIP_IP6_FRAG=y
|
||||||
# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set
|
# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set
|
||||||
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
||||||
CONFIG_LWIP_GARP_TMR_INTERVAL=60
|
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_TCPIP_RECVMBOX_SIZE=32
|
||||||
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
||||||
# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set
|
# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set
|
||||||
CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y
|
CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y
|
||||||
# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set
|
# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set
|
||||||
CONFIG_LWIP_DHCP_OPTIONS_LEN=68
|
CONFIG_LWIP_DHCP_OPTIONS_LEN=68
|
||||||
CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# DHCP server
|
# DHCP server
|
||||||
|
@ -712,7 +688,6 @@ CONFIG_LWIP_TCP_SYNMAXRTX=6
|
||||||
CONFIG_LWIP_TCP_MSS=1436
|
CONFIG_LWIP_TCP_MSS=1436
|
||||||
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
||||||
CONFIG_LWIP_TCP_MSL=60000
|
CONFIG_LWIP_TCP_MSL=60000
|
||||||
CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000
|
|
||||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
||||||
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
||||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||||
|
@ -828,7 +803,6 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y
|
||||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
||||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
||||||
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
||||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200
|
|
||||||
# end of Certificate Bundle
|
# end of Certificate Bundle
|
||||||
|
|
||||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||||
|
@ -947,7 +921,6 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||||
#
|
#
|
||||||
# NVS
|
# NVS
|
||||||
#
|
#
|
||||||
# CONFIG_NVS_ASSERT_ERROR_CHECK is not set
|
|
||||||
# end of NVS
|
# end of NVS
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -1016,6 +989,7 @@ CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||||
# Host File System I/O (Semihosting)
|
# Host File System I/O (Semihosting)
|
||||||
#
|
#
|
||||||
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
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 Host File System I/O (Semihosting)
|
||||||
# end of Virtual file system
|
# end of Virtual file system
|
||||||
|
|
||||||
|
@ -1157,7 +1131,6 @@ CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y
|
||||||
CONFIG_ESP32_ENABLE_COREDUMP=y
|
CONFIG_ESP32_ENABLE_COREDUMP=y
|
||||||
CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64
|
CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64
|
||||||
CONFIG_ESP32_CORE_DUMP_UART_DELAY=0
|
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_INFO=y
|
||||||
# CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set
|
# CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set
|
||||||
CONFIG_ESP32_CORE_DUMP_DECODE="info"
|
CONFIG_ESP32_CORE_DUMP_DECODE="info"
|
||||||
|
@ -1203,4 +1176,5 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
||||||
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||||
CONFIG_SUPPORT_TERMIOS=y
|
CONFIG_SUPPORT_TERMIOS=y
|
||||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||||
|
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||||
# End of deprecated options
|
# End of deprecated options
|
||||||
|
|
|
@ -189,7 +189,6 @@ CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||||
#
|
#
|
||||||
# CONFIG_ADC_FORCE_XPD_FSM is not set
|
# CONFIG_ADC_FORCE_XPD_FSM is not set
|
||||||
CONFIG_ADC_DISABLE_DAC=y
|
CONFIG_ADC_DISABLE_DAC=y
|
||||||
# CONFIG_ADC_CONTINUOUS_FORCE_USE_ADC2_ON_C3_S3 is not set
|
|
||||||
# end of ADC configuration
|
# end of ADC configuration
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -211,7 +210,6 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||||
# TWAI configuration
|
# TWAI configuration
|
||||||
#
|
#
|
||||||
# CONFIG_TWAI_ISR_IN_IRAM is not set
|
# CONFIG_TWAI_ISR_IN_IRAM is not set
|
||||||
# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set
|
|
||||||
# end of TWAI configuration
|
# end of TWAI configuration
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -239,14 +237,6 @@ CONFIG_EFUSE_MAX_BLK_LEN=256
|
||||||
#
|
#
|
||||||
# ESP32S3-Specific
|
# ESP32S3-Specific
|
||||||
#
|
#
|
||||||
CONFIG_ESP32S3_REV_MIN_0=y
|
|
||||||
# CONFIG_ESP32S3_REV_MIN_1 is not set
|
|
||||||
# CONFIG_ESP32S3_REV_MIN_2 is not set
|
|
||||||
CONFIG_ESP32S3_REV_MIN_FULL=0
|
|
||||||
CONFIG_ESP_REV_MIN_FULL=0
|
|
||||||
CONFIG_ESP32S3_REV_MAX_FULL_STR_OPT=y
|
|
||||||
CONFIG_ESP32S3_REV_MAX_FULL=99
|
|
||||||
CONFIG_ESP_REV_MAX_FULL=99
|
|
||||||
# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_80 is not set
|
# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_80 is not set
|
||||||
CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160=y
|
CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160=y
|
||||||
# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240 is not set
|
# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240 is not set
|
||||||
|
@ -411,13 +401,6 @@ CONFIG_PM_POWER_DOWN_CPU_IN_LIGHT_SLEEP=y
|
||||||
CONFIG_PM_POWER_DOWN_TAGMEM_IN_LIGHT_SLEEP=y
|
CONFIG_PM_POWER_DOWN_TAGMEM_IN_LIGHT_SLEEP=y
|
||||||
# end of Power Management
|
# 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
|
# ESP System Settings
|
||||||
#
|
#
|
||||||
|
@ -507,8 +490,6 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y
|
||||||
# CONFIG_ESP_WIFI_GCMP_SUPPORT is not set
|
# CONFIG_ESP_WIFI_GCMP_SUPPORT is not set
|
||||||
# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set
|
# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set
|
||||||
CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y
|
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
|
# end of Wi-Fi
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -645,7 +626,6 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y
|
||||||
CONFIG_LWIP_LOCAL_HOSTNAME="espressif"
|
CONFIG_LWIP_LOCAL_HOSTNAME="espressif"
|
||||||
# CONFIG_LWIP_NETIF_API is not set
|
# CONFIG_LWIP_NETIF_API is not set
|
||||||
# CONFIG_LWIP_TCPIP_CORE_LOCKING is not set
|
# 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_DNS_SUPPORT_MDNS_QUERIES=y
|
||||||
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
# CONFIG_LWIP_L2_TO_L3_COPY is not set
|
||||||
# CONFIG_LWIP_IRAM_OPTIMIZATION is not set
|
# CONFIG_LWIP_IRAM_OPTIMIZATION is not set
|
||||||
|
@ -666,15 +646,12 @@ CONFIG_LWIP_IP6_FRAG=y
|
||||||
# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set
|
# CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set
|
||||||
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
||||||
CONFIG_LWIP_GARP_TMR_INTERVAL=60
|
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_TCPIP_RECVMBOX_SIZE=32
|
||||||
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y
|
||||||
# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set
|
# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set
|
||||||
CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y
|
CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y
|
||||||
# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set
|
# CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set
|
||||||
CONFIG_LWIP_DHCP_OPTIONS_LEN=68
|
CONFIG_LWIP_DHCP_OPTIONS_LEN=68
|
||||||
CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# DHCP server
|
# DHCP server
|
||||||
|
@ -704,7 +681,6 @@ CONFIG_LWIP_TCP_SYNMAXRTX=12
|
||||||
CONFIG_LWIP_TCP_MSS=1440
|
CONFIG_LWIP_TCP_MSS=1440
|
||||||
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
CONFIG_LWIP_TCP_TMR_INTERVAL=250
|
||||||
CONFIG_LWIP_TCP_MSL=60000
|
CONFIG_LWIP_TCP_MSL=60000
|
||||||
CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000
|
|
||||||
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
|
||||||
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
CONFIG_LWIP_TCP_WND_DEFAULT=5744
|
||||||
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
CONFIG_LWIP_TCP_RECVMBOX_SIZE=6
|
||||||
|
@ -815,7 +791,6 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y
|
||||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
||||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
||||||
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
||||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200
|
|
||||||
# end of Certificate Bundle
|
# end of Certificate Bundle
|
||||||
|
|
||||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||||
|
@ -932,7 +907,6 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||||
#
|
#
|
||||||
# NVS
|
# NVS
|
||||||
#
|
#
|
||||||
# CONFIG_NVS_ASSERT_ERROR_CHECK is not set
|
|
||||||
# end of NVS
|
# end of NVS
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -1003,6 +977,7 @@ CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||||
# Host File System I/O (Semihosting)
|
# Host File System I/O (Semihosting)
|
||||||
#
|
#
|
||||||
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
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 Host File System I/O (Semihosting)
|
||||||
# end of Virtual file system
|
# end of Virtual file system
|
||||||
|
|
||||||
|
@ -1156,4 +1131,5 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
||||||
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||||
CONFIG_SUPPORT_TERMIOS=y
|
CONFIG_SUPPORT_TERMIOS=y
|
||||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||||
|
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||||
# End of deprecated options
|
# End of deprecated options
|
||||||
|
|
Loading…
Reference in New Issue