mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ESP32: set default cpu frequency to 240MHz
Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
parent
a14fb9ab28
commit
3c561e215f
@ -10,6 +10,7 @@ CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
|
||||
CONFIG_ESPTOOLPY_FLASHMODE_QIO=y
|
||||
CONFIG_ESPTOOLPY_FLASHFREQ_80M=y
|
||||
CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y
|
||||
CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y
|
||||
CONFIG_PARTITION_TABLE_CUSTOM=y
|
||||
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv"
|
||||
CONFIG_COMPILER_OPTIMIZATION_PERF=y
|
||||
|
@ -20,6 +20,7 @@ CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_TWO=y
|
||||
CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=n
|
||||
CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND=n
|
||||
CONFIG_ESP32S3_INSTRUCTION_CACHE_32KB=y
|
||||
CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y
|
||||
CONFIG_ESP_INT_WDT=n
|
||||
CONFIG_ESP_TASK_WDT_INIT=n
|
||||
CONFIG_ESP_IPC_TASK_STACK_SIZE=1536
|
||||
|
Loading…
Reference in New Issue
Block a user