AP_HAL_ESP32: Migration of ESP32 targets from idf 4.4 to 5.3 consisting of:

- modification of CMakeLists to use new component names of idf 5.3;
- removing big sdkconfig, which changes a lot, when upgrading idf and to use sdkconfig.defaults, which contain only non default defines;
- Updated idf installation packages list, according to espressif documentation;
- Updated README.md to reflect changes in sdkconfig handling;
- Fixed WDT in Scheduler, it was broken with idf 5.3;
- fixed compilation issues with GCC 13 (which is used by idf 5.3);
- fixed bug in case when HAL_ESP32_WIFI defined as 0 (disable wifi)
- Added ESP32 targets sdkconfig (auto generated) to .gitignore
This commit is contained in:
ARg 2024-09-25 12:10:08 +02:00 committed by Andrew Tridgell
parent b234729398
commit 1ef0f1a63f
19 changed files with 195 additions and 2449 deletions

4
.gitignore vendored
View File

@ -171,3 +171,7 @@ ENV/
env.bak/
venv.bak/
autotest_result_*_junit.xml
# Ignore ESP-IDF SDK defines
/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig
/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig

View File

@ -32,13 +32,14 @@
#include <AP_HAL/SIMState.h>
#endif
static ESP32::UARTDriver cons(0);
#ifdef HAL_ESP32_WIFI
#if HAL_ESP32_WIFI == 1
static ESP32::WiFiDriver serial1Driver; //tcp, client should connect to 192.168.4.1 port 5760
#elif HAL_ESP32_WIFI == 2
static ESP32::WiFiUdpDriver serial1Driver; //udp
#else
static Empty::UARTDriver serial1Driver;
#endif
#else
static Empty::UARTDriver serial1Driver;

View File

@ -14,11 +14,11 @@ or
Tools/environment_install/install-prereqs-arch.sh
```
3. install esp-idf python deps:
2. install esp-idf python deps:
```
# from: https://docs.espressif.com/projects/esp-idf/en/latest/esp32/get-started/linux-setup.html
sudo apt-get install git wget flex bison gperf python-setuptools cmake ninja-build ccache libffi-dev libssl-dev dfu-util
sudo apt-get install git wget flex bison gperf cmake ninja-build ccache libffi-dev libssl-dev dfu-util
sudo apt-get install python3 python3-pip python3-setuptools
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10
@ -61,7 +61,7 @@ TIPS:
- we use toolchain and esp-idf from espressif , as a 'git submodule', so no need to preinstall etc.
https://docs.espressif.com/projects/esp-idf/en/latest/get-started/ -
(note we currently use https://github.com/espressif/esp-idf/tree/release/v4.0 )
(note we currently use https://github.com/espressif/esp-idf/tree/release/v5.3 )
- if you get compile error/s to do with CONFIG... such as
@ -69,7 +69,12 @@ in expansion of macro 'configSUPPORT_STATIC_ALLOCATION'
warning: "CONFIG_SUPPORT_STATIC_ALLOCATION" is not defined
this means your 'sdkconfig' file that the IDF relies on is perhaps a bit out of date or out of sync with your IDF.
So double check you are using the correct IDF version ( buzz's branch uses v3.3 , sh83's probably does not.. and then if you are sure:
You can simply remove sdkconfig file and idf build system will recreate it using sdkconfig.defaults, which should fix the problem.
If you need to change sdkconfig, you can edit sdkconfig manually or to use ninja menuconfig:
So double check you are using the correct IDF version:
```
cd build/esp32{BOARD}/esp-idf_build
ninja menuconfig
@ -81,11 +86,7 @@ press [tab] then enter on the [exit] box to exit the app
done. the 'sdkconfig' file in this folder should have been updated
cd ../../../..
OR locate the 'libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig' and delete it, as it should call back to the 'sdkconfig.defaults' file if its not there.
'cd libraries/AP_HAL_ESP32/targets/esp32/esp-idf ; idf.py defconfig' is the command that updates it, but that shouldn't be needed manually, we don't think.
... try ./waf plane"
If you want to make changes to sdkconfig (sdkconfig is in git ignore list) permanent and to commit them back in git, you should edit sdkconfig.defaults manually or to use ninja save-defconfig tool after menuconfig.
5. Recommanded way to flash the firmware :
```
@ -114,9 +115,6 @@ ESPTOOL_BAUD=921600
You can find more info here : [ESPTOOL](https://github.com/espressif/esptool)
You can also find the cmake esp-idf project at `libraries/AP_HAL_ESP32/targets/esp32/esp-idf` for idf.py command. But see next section to understand how ardupilot is compiled on ESP32.
For flashing from another machine you need the following files:
```
build/<board>/esp-idf_build/bootloader/bootloader.bin

View File

@ -60,7 +60,7 @@ SPIDevice::SPIDevice(SPIBus &_bus, SPIDeviceDesc &_device_desc)
set_device_bus(bus.bus);
set_device_address(_device_desc.device);
set_speed(AP_HAL::Device::SPEED_LOW);
gpio_pad_select_gpio(device_desc.cs);
esp_rom_gpio_pad_select_gpio(device_desc.cs);
gpio_set_direction(device_desc.cs, GPIO_MODE_OUTPUT);
gpio_set_level(device_desc.cs, 1);

View File

@ -23,8 +23,6 @@
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "soc/rtc_wdt.h"
#include "esp_int_wdt.h"
#include "esp_task_wdt.h"
#include <AP_HAL/AP_HAL.h>
@ -38,39 +36,33 @@ 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()
{
_initialized = false;
}
void disableCore0WDT()
Scheduler::~Scheduler()
{
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");
if (_initialized) {
esp_task_wdt_deinit();
}
}
void disableCore1WDT()
void Scheduler::wdt_init(uint32_t timeout, uint32_t core_mask)
{
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");
esp_task_wdt_config_t config = {
.timeout_ms = timeout,
.idle_core_mask = core_mask,
.trigger_panic = true
};
if ( ESP_OK != esp_task_wdt_init(&config) ) {
printf("esp_task_wdt_init() failed\n");
}
}
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");
if (ESP_OK != esp_task_wdt_add(NULL)) {
printf("esp_task_wdt_add(NULL) failed");
}
}
@ -81,11 +73,6 @@ 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
@ -140,11 +127,6 @@ void Scheduler::init()
}
// xTaskCreatePinnedToCore(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr,SLOWCPU);
hal.console->printf("OK Sched Init, enabling WD\n");
enableCore0WDT(); //FASTCPU
//enableCore1WDT(); //we don't enable WD on SLOWCPU right now.
}
template <typename T>
@ -232,7 +214,7 @@ void IRAM_ATTR Scheduler::delay(uint16_t ms)
void IRAM_ATTR Scheduler::delay_microseconds(uint16_t us)
{
if (in_main_thread() && us < 100) {
ets_delay_us(us);
esp_rom_delay_us(us);
} else { // Minimum delay for FreeRTOS is 1ms
uint32_t tick = portTICK_PERIOD_MS * 1000;
@ -571,6 +553,10 @@ void IRAM_ATTR Scheduler::_main_thread(void *arg)
sched->set_system_initialized();
//initialize WTD for current thread on FASTCPU, all cores will be (1 << CONFIG_FREERTOS_NUMBER_OF_CORES) - 1
wdt_init( TWDT_TIMEOUT_MS, 1 << FASTCPU ); // 3 sec
#ifdef SCHEDDEBUG
printf("%s:%d initialised\n", __PRETTY_FUNCTION__, __LINE__);
#endif
@ -581,6 +567,10 @@ void IRAM_ATTR Scheduler::_main_thread(void *arg)
// run stats periodically
sched->print_stats();
sched->print_main_loop_rate();
if (ESP_OK != esp_task_wdt_reset()) {
printf("esp_task_wdt_reset() failed\n");
};
}
}

View File

@ -23,7 +23,7 @@
#define ESP32_SCHEDULER_MAX_TIMER_PROCS 10
#define ESP32_SCHEDULER_MAX_IO_PROCS 10
#define TWDT_TIMEOUT_MS 3000
/* Scheduler implementation: */
class ESP32::Scheduler : public AP_HAL::Scheduler
@ -31,6 +31,7 @@ class ESP32::Scheduler : public AP_HAL::Scheduler
public:
Scheduler();
~Scheduler();
/* AP_HAL::Scheduler methods */
void init() override;
void set_callbacks(AP_HAL::HAL::Callbacks *cb)
@ -130,6 +131,8 @@ private:
static void test_esc(void* arg);
static void wdt_init(uint32_t timeout, uint32_t core_mask);
bool _in_timer_proc;
void _run_timers();
Semaphore _timer_sem;

View File

@ -32,8 +32,6 @@
#include <sys/types.h>
#include "SPIDevice.h"
#include "soc/rtc_wdt.h"
#ifdef HAL_ESP32_SDCARD
#if CONFIG_IDF_TARGET_ESP32S2 ||CONFIG_IDF_TARGET_ESP32C3
@ -254,8 +252,8 @@ void mount_sdcard()
{
mount_sdcard_spi();
}
#endif // end spi
#endif // end spi
bool sdcard_retry(void)
{
@ -265,16 +263,14 @@ bool sdcard_retry(void)
return sdcard_running;
}
void unmount_sdcard()
{
if (card != nullptr) {
esp_vfs_fat_sdmmc_unmount();
esp_vfs_fat_sdcard_unmount( "/SDCARD", card);
}
sdcard_running = false;
}
#else
// empty impl's
void mount_sdcard()

View File

@ -106,7 +106,7 @@ void BinarySemaphore::signal_ISR()
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
xSemaphoreGiveFromISR(_sem, &xHigherPriorityTaskWoken);
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
portYIELD_FROM_ISR_ARG(xHigherPriorityTaskWoken);
}
BinarySemaphore::~BinarySemaphore(void)

View File

@ -55,7 +55,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
uart_desc[uart_num].rx,
UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
//uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0);
uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0);
uart_driver_install(p, 2*UART_HW_FIFO_LEN(p), 0, 0, nullptr, 0);
_readbuf.set_size(RX_BUF_SIZE);
_writebuf.set_size(TX_BUF_SIZE);

View File

@ -35,6 +35,7 @@
#include "esp_heap_caps.h"
#include <AP_Common/ExpandingString.h>
#include "esp_mac.h"
extern const AP_HAL::HAL& hal;

View File

@ -145,7 +145,7 @@ bool WiFiDriver::start_listen()
bool WiFiDriver::try_accept()
{
struct sockaddr_in sourceAddr;
uint addrLen = sizeof(sourceAddr);
socklen_t addrLen = sizeof(sourceAddr);
short i = available_socket();
if (i != WIFI_MAX_CONNECTION) {
socket_list[i] = accept(accept_socket, (struct sockaddr *)&sourceAddr, &addrLen);
@ -246,7 +246,7 @@ static void _sta_event_handler(void* arg, esp_event_base_t event_base,
void WiFiDriver::initialize_wifi()
{
#ifndef WIFI_PWD
#default WIFI_PWD "ardupilot1"
#define WIFI_PWD "ardupilot1"
#endif
//Initialize NVS
esp_err_t ret = nvs_flash_init();

View File

@ -32,7 +32,7 @@
#include "lwip/sys.h"
#include "lwip/netdb.h"
#include "soc/rtc_wdt.h"
#include "freertos/idf_additions.h"
using namespace ESP32;
@ -215,7 +215,7 @@ static void _sta_event_handler(void* arg, esp_event_base_t event_base,
void WiFiUdpDriver::initialize_wifi()
{
#ifndef WIFI_PWD
#default WIFI_PWD "ardupilot1"
#define WIFI_PWD "ardupilot1"
#endif
//Initialize NVS
esp_err_t ret = nvs_flash_init();

View File

@ -126,8 +126,9 @@ void i2c_init(_i2c_bus_t* bus)
case 160: bus->delay = _i2c_delays[bus->speed][1]; break;
case 240: bus->delay = _i2c_delays[bus->speed][2]; break;
default : DEBUG("i2c I2C software implementation is not "
"supported for this CPU frequency: %d MHz\n",
ets_get_cpu_frequency());
"supported for this CPU frequency: %u MHz\n",
(unsigned int)ets_get_cpu_frequency()
);
return;
}

View File

@ -15,15 +15,22 @@ idf_build_process(esp32
# although esptool_py does not generate static library,
# processing the component is needed for flashing related
# targets and file generation
COMPONENTS esp32
freertos
tcpip_adapter
fatfs
esp_adc_cal
nvs_flash
esptool_py
app_update
COMPONENTS freertos
fatfs
nvs_flash
esptool_py
app_update
esp_adc
esp_driver_mcpwm
driver
lwip
esp_wifi
esp_system
esp_rom
esp_timer
SDKCONFIG ${CMAKE_CURRENT_LIST_DIR}/sdkconfig
SDKCONFIG_DEFAULTS ${CMAKE_CURRENT_LIST_DIR}/sdkconfig.defaults
BUILD_DIR ${CMAKE_BINARY_DIR})
set(elf_file ardupilot.elf)
@ -94,14 +101,19 @@ add_custom_target(showinc ALL
# Link the static libraries to the executable
target_link_libraries(${elf_file}
idf::esp32
idf::freertos
idf::fatfs
idf::esp_adc_cal
idf::nvs_flash
idf::spi_flash
idf::tcpip_adapter
idf::app_update
idf::esp_adc
idf::esp_driver_mcpwm
idf::driver
idf::lwip
idf::esp_wifi
idf::esp_system
idf::esp_rom
idf::esp_timer
)
# Attach additional targets to the executable file for flashing,

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,51 @@
# This file was generated using idf.py save-defconfig. It can be edited manually.
# Espressif IoT Development Framework (ESP-IDF) 5.3.1 Project Minimal Configuration
#
CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y
CONFIG_BOOTLOADER_WDT_ENABLE=n
CONFIG_APP_COMPILE_TIME_DATE=n
CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y
CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y
CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
CONFIG_ESPTOOLPY_FLASHMODE_QIO=y
CONFIG_ESPTOOLPY_FLASHFREQ_80M=y
CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y
CONFIG_PARTITION_TABLE_CUSTOM=y
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv"
CONFIG_COMPILER_OPTIMIZATION_PERF=y
CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC=n
CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST=n
CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID=n
CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT=n
CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=n
CONFIG_SPI_MASTER_IN_IRAM=y
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y
CONFIG_ESP_PHY_REDUCE_TX_POWER=y
CONFIG_PM_ENABLE=y
CONFIG_ESP_INT_WDT=n
CONFIG_ESP_TASK_WDT_INIT=n
CONFIG_ESP_WIFI_STATIC_RX_BUFFER_NUM=2
CONFIG_ESP_WIFI_DYNAMIC_RX_BUFFER_NUM=16
CONFIG_ESP_WIFI_DYNAMIC_TX_BUFFER_NUM=16
CONFIG_ESP_WIFI_RX_BA_WIN=4
CONFIG_ESP_WIFI_TASK_PINNED_TO_CORE_1=y
CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE=n
CONFIG_ESP_WIFI_GMAC_SUPPORT=n
CONFIG_FREERTOS_HZ=1000
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10
CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y
CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y
CONFIG_FREERTOS_ISR_STACKSIZE=2100
CONFIG_FREERTOS_CORETIMER_1=y
CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY=y
CONFIG_LWIP_MAX_SOCKETS=5
CONFIG_LWIP_TCP_SYNMAXRTX=6
CONFIG_LWIP_TCP_MSS=1436
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
CONFIG_LWIP_TCP_WND_DEFAULT=5744
CONFIG_LWIP_TCP_RTO_TIME=3000
CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y
CONFIG_ADC_SUPPRESS_DEPRECATE_WARN=y
CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN=y
CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN=y
CONFIG_RMT_SUPPRESS_DEPRECATE_WARN=y

View File

@ -15,16 +15,24 @@ idf_build_process(esp32s3
# although esptool_py does not generate static library,
# processing the component is needed for flashing related
# targets and file generation
COMPONENTS esp32s3
freertos
tcpip_adapter
COMPONENTS freertos
fatfs
esp_adc_cal
nvs_flash
esptool_py
app_update
esp_adc
esp_driver_mcpwm
driver
lwip
esp_wifi
esp_system
esp_rom
esp_timer
SDKCONFIG ${CMAKE_CURRENT_LIST_DIR}/sdkconfig
BUILD_DIR ${CMAKE_BINARY_DIR})
SDKCONFIG_DEFAULTS ${CMAKE_CURRENT_LIST_DIR}/sdkconfig.defaults
BUILD_DIR ${CMAKE_BINARY_DIR}
)
set(elf_file ardupilot.elf)
@ -93,14 +101,19 @@ add_custom_target(showinc ALL
# Link the static libraries to the executable
target_link_libraries(${elf_file}
idf::esp32s3
idf::freertos
idf::fatfs
idf::esp_adc_cal
idf::nvs_flash
idf::spi_flash
idf::tcpip_adapter
idf::app_update
idf::esp_adc
idf::esp_driver_mcpwm
idf::driver
idf::lwip
idf::esp_wifi
idf::esp_system
idf::esp_rom
idf::esp_timer
)
# Attach additional targets to the executable file for flashing,

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,43 @@
# This file was generated using idf.py save-defconfig. It can be edited manually.
# Espressif IoT Development Framework (ESP-IDF) 5.3.1 Project Minimal Configuration
#
CONFIG_IDF_TARGET="esp32s3"
CONFIG_BOOTLOADER_LOG_LEVEL_ERROR=y
CONFIG_BOOTLOADER_WDT_ENABLE=n
CONFIG_APP_COMPILE_TIME_DATE=n
CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y
CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y
CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
CONFIG_ESPTOOLPY_FLASHMODE_QIO=y
CONFIG_ESPTOOLPY_FLASHSIZE_8MB=y
CONFIG_PARTITION_TABLE_CUSTOM=y
CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="../partitions.csv"
CONFIG_PARTITION_TABLE_OFFSET=0x10000
CONFIG_COMPILER_OPTIMIZATION_PERF=y
CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM=n
CONFIG_SPI_MASTER_IN_IRAM=y
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_INT_WDT=n
CONFIG_ESP_TASK_WDT_INIT=n
CONFIG_ESP_IPC_TASK_STACK_SIZE=1536
CONFIG_ESP_WIFI_TASK_PINNED_TO_CORE_1=y
CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE=n
CONFIG_ESP_WIFI_GMAC_SUPPORT=n
CONFIG_FREERTOS_HZ=1000
CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=10
CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID=y
CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS=y
CONFIG_FREERTOS_ISR_STACKSIZE=2100
CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3=y
CONFIG_FREERTOS_ENABLE_BACKWARD_COMPATIBILITY=y
CONFIG_LWIP_MAX_SOCKETS=5
CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744
CONFIG_LWIP_TCP_WND_DEFAULT=5744
CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1=y
CONFIG_ADC_SUPPRESS_DEPRECATE_WARN=y
CONFIG_ADC_CALI_SUPPRESS_DEPRECATE_WARN=y
CONFIG_MCPWM_SUPPRESS_DEPRECATE_WARN=y
CONFIG_RMT_SUPPRESS_DEPRECATE_WARN=y