Learning Ardupilot, starting with ESP32

  1. Update Apr 21,2024

Got also the Heli firmware on ESP32 working in principle.
I had to change

  • libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeList.txt
    added a new target to the 2. if-loop:
    ELSEIF(${ARDUPILOT_CMD} STREQUAL “heli”)
    message(“Building for heli”)
    target_link_libraries(${elf_file} “${ARDUPILOT_BIN}/libarducopter-heli.a”)
    target_link_libraries(${elf_file} “${ARDUPILOT_LIB}/libArduCopter_libs.a”)

Update Apr 21,2024
Today I tried to build a Heli firmware for my ESP32 board. But it failed.
Bulding of plane and copter version was prior successfull.
In general building of a Heli firmware worked. this I tested by building a firmware for a matekH743 board. So my general build enviroment and my commands seems to be ok.
But not for the ESP32 board
One difference I saw on the console:
Building the copter version the console shows

– Build files have been written to: /home/juergen/ardupilot/build/esp32famos1/esp-idf_build
ARDUPILOT_CMD=copter
WAF_BUILD_TARGET=
Building for copter

[2/3] CMake Build esp-idf showinc

while on building the heli version the console shows:

– Build files have been written to: /home/juergen/ardupilot/build/esp32famos1/esp-idf_build
ARDUPILOT_CMD=heli
WAF_BUILD_TARGET=
CMake Warning:
Manually-specified variables were not used by the project:

ARDUPILOT_BIN
ARDUPILOT_LIB

[2/3] CMake Build esp-idf showinc

hm, at the moment I am little struggling, missing the right idea.

Update Apr 19,2024
As I am not able to reply to my own thread I have now changed the sequence to have always the newest information on top
(PS: I am sorry but I don’t know how to change this behavior, maybe a moderator can look at this)
Today I had my first successful arming and basic (cheated) “testflight” with my development board.

Any suggestions or remarks :-))

Update Apr 17, 2024
Now the HW - Test platform is completed with SD-Card and IMU MPU6050

The SD Card is connected to the standard vspi bus on the esp32 board and the IMU is also connected to the standard I2C bus. For this small changes at my new libraries/AP_HAL_ESP32/boards/esp32famos1.h was necessary as the esp32empty.h had some mismatch and doubled used gpio-pins.

(PS: I am sorry to only use update function as I cannot reply to my own thread. Don’t know how to change this, maybe a moderator can look at this)

Update Apr 10,2024
After setting up the development enviroment and programming the first ESP32 with a ardupilot firmware I had the first success as the module shows up on mission planner.
After getting some initial messages during startup in the message window I got some PreArm messages

  • 3D Accel calibration needed
  • AHRS: waiting for home
  • Waiting for RC

The first two messages are clear as my board has no IMU and no GPS connection. It is just the simple ESP32 Dev board.
But the last one is a small disappointment as I had a RC receiver connected to the defined HAL_ESP32_RCIN GPIO_NUM_36.
Also on the setup page I don’t see any reaction on my RC calibration tab.
My radio system is a good old Futaba TX and RX using SBUS on the RX output.
OK, I had to go deaper in the board definition file.
Therefore I decided first to create my own submodule type.

  • copied the existing board definition file
    libraries/AP_HAL_ESP32/boards/esp32empty.h to esp32famos1.h
  • copied existing hwdef folder
    libraries/AP_HAL_ESP32/hwdef/esp32empty to esp32famos1
  • edit libraries/AP_HAL_ESP32/boards/esp32famos1.h
    change #define HAL_ESP32_BOARD_NAME to “esp32-famos1”
    change #define HAL_ESP32_RMT_RX_PIN__NUMBER to 36
    comment out #define AP_RCPROTOCOL_ENABLED 0

After this changes I got two compiler errors and therefore I also had to change

  • libraries/AP_HAL/AP_HAL_Boards.h
    add #define HAL_BOARD_SUBTYPE_ESP32_FAMOS1 6009
  • libraries/AP_HAL/board/esp32.h
    add #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD-SUBTYPE_ESP32_FAMOS1
    add #include “esp32famos1.h”

Now compiling runs well and I uploaded the new firmware.
After startup the module shows detection of SBUS receiver correctly and also I was able to check the RC input on the setup tab.

Again good success for today

START April 5, 2024
Hi everybody,
now I did it. The first step in the ardupilot world. With the help of this nice forum.
For a while I am looking for a platform, which I can use as flight controller for a future planned twin rotor helicopter. To built such a basically radio controlled helicopter is dream since decades of years. Now, as pensioner maybe i can realize this youth dream. One part of the way is to built a own flight controller or to adapt existing one.
Therefore I started two approaches.
First approach is a develoment with arduino ide, C-programming based on a Teensy board only for stabilizing functions but not autonomous flight control
Second approach adaption of ardupilot with open end.
To learn more about ardupilot I just started with the next step after only reading the forum and the ardupilot sites.
I installed on a spare Win10 notebook the development enviroment for ardupilot and started today to compile and flash my first ardupilot capable controller board, a bare ESP32 WROOM 32 , as I have some of these boards available.
At the moment the board is not doing much, no sensors, just talking mavlink with mission planer. It is only a very first step.
But as I am not a SW-Developer I must learn all this in small steps.
All information, how to setup the enviroment with the specials for ESP32 I found here and on the ardupilot wikis.
Therefore I say thankyou to you, the developers and this community.

WHAT I DID YESTERDAY Apr.4;2024
Steps I did till yesterday:
Setting up the buid enviroment on WIN 10 Notebook following the
https://ardupilot.org/dev/docs/building-setup-windows10_new.html Steps 1 - 3.
Most problem was enabling the WSL function on the Notebook as

  1. the support of virtual engine must be enabled in Notebook BIOS
  2. Antivirus software must be disabled during install

Afterwards I followed the git command line setup
https://ardupilot.org/dev/docs/building-setup-linux.html
and just cloned the ardupilot repository with the command line as described on the above mentioned page to the virtual ubuntu system and executet the shown script for installing the required packages
To check the installation i run a test build like shown here:
https://github.com/ArduPilot/ardupilot/blob/master/BUILD.md
./waf configure board --MatekH743
./waf heli
I selected this test build as for the far futre twin helicopter i think this might be the best board.
This test build run without any problems on the fresh installed virtual ubuntu system and shows that the build enviroment is in principle set up.
As I don’t have such a board available but some ESP32 I decided to start with this an learn further
To use the ESP32 additional tools are necessary. For this I followed
https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_ESP32/README.md Step 3
Also this worked fine.
But on Step 4 I got an error during the linking prozess.
The reason was probably that I don’t run ./waf distclean before starting with the new setup.
So the next try
./waf distclean
./waf configure
./waf configure --board esp32empty
./waf plane
runs without errors and generates the correct output files
The next problem shows up with the upload as shown in step 5
ESPBAUD=921600 ./waf plane --upload
The tool could not find my ESP32 board connected to COM4 via USB. But this is a known problem of the ESP32 board. It dosn’t start in bootloader mode. It is necessary to press the boot buttom on the board until the download starts. So on the next try I pressed for a very long time this buttom and than also the upload worked.
Finally I connected the board via USB to mission planer and can see it is communicating with mission planer.

9 Likes

Moved to “Other Hardware” to open replies.

1 Like

You are my king, thank you Yuri. :grinning:
After I started this topic I wasn’t able to reply on my own topic so I used the “edit” function for updates which was not nice.
After Yuri’s help i am now able to restructure this topic little more for updating from time to time.

  1. Update Apr 10,2024

After setting up the development enviroment and programming the first ESP32 with a ardupilot firmware I had the first success as the module shows up on mission planner.
After getting some initial messages during startup in the message window I got some PreArm messages

  • 3D Accel calibration needed
  • AHRS: waiting for home
  • Waiting for RC

The first two messages are clear as my board has no IMU and no GPS connection. It is just the simple ESP32 Dev board.
But the last one is a small disappointment as I had a RC receiver connected to the defined HAL_ESP32_RCIN GPIO_NUM_36.
Also on the setup page I don’t see any reaction on my RC calibration tab.
My radio system is a good old Futaba TX and RX using SBUS on the RX output.
OK, I had to go deaper in the board definition file.
Therefore I decided first to create my own submodule type.

  • copied the existing board definition file
    libraries/AP_HAL_ESP32/boards/esp32empty.h to esp32famos1.h
  • copied existing hwdef folder
    libraries/AP_HAL_ESP32/hwdef/esp32empty to esp32famos1
  • edit libraries/AP_HAL_ESP32/boards/esp32famos1.h
    change #define HAL_ESP32_BOARD_NAME to “esp32-famos1”
    change #define HAL_ESP32_RMT_RX_PIN__NUMBER to 36
    comment out #define AP_RCPROTOCOL_ENABLED 0

After this changes I got two compiler errors and therefore I also had to change

  • libraries/AP_HAL/AP_HAL_Boards.h
    add #define HAL_BOARD_SUBTYPE_ESP32_FAMOS1 6009
  • libraries/AP_HAL/board/esp32.h
    add #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD-SUBTYPE_ESP32_FAMOS1
    add #include “esp32famos1.h”

Now compiling runs well and I uploaded the new firmware.
After startup the module shows detection of SBUS receiver correctly and also I was able to check the RC input on the setup tab.

Again good success for today

1 Like
  1. Update Apr 17, 2024

Now the HW - Test platform is completed with SD-Card and IMU MPU6050

The SD Card is connected to the standard vspi bus on the esp32 board and the IMU is also connected to the standard I2C bus. For this small changes at my new libraries/AP_HAL_ESP32/boards/esp32famos1.h was necessary as the esp32empty.h had some mismatch and doubled used gpio-pins.

1 Like
  1. Update Apr 19,2024

As I am not able to reply to my own thread I have now changed the sequence to have always the newest information on top
(PS: I am sorry but I don’t know how to change this behavior, maybe a moderator can look at this)
Today I had my first successful arming and basic (cheated) “testflight” with my development board.

Any suggestions or remarks :-))

1 Like
  1. Update Apr 21,2024

Today I tried to build a Heli firmware for my ESP32 board. But it failed.
Bulding of plane and copter version was prior successfull.
In general building of a Heli firmware worked. this I tested by building a firmware for a matekH743 board. So my general build enviroment and my commands seems to be ok.
But not for the ESP32 board
One difference I saw on the console:
Building the copter version the console shows

– Build files have been written to: /home/juergen/ardupilot/build/esp32famos1/esp-idf_build
ARDUPILOT_CMD=copter
WAF_BUILD_TARGET=
Building for copter

[2/3] CMake Build esp-idf showinc

while on building the heli version the console shows:

– Build files have been written to: /home/juergen/ardupilot/build/esp32famos1/esp-idf_build
ARDUPILOT_CMD=heli
WAF_BUILD_TARGET=
CMake Warning:
Manually-specified variables were not used by the project:

ARDUPILOT_BIN
ARDUPILOT_LIB

[2/3] CMake Build esp-idf showinc

hm, at the moment I am little struggling, missing the right idea.

  1. Update Apr 21,2024

Got also the Heli firmware on ESP32 working in principle.
I had to change

  • libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeList.txt
    added a new target to the 2. if-loop:
    ELSEIF(${ARDUPILOT_CMD} STREQUAL “heli”)
    message(“Building for heli”)
    target_link_libraries(${elf_file} “${ARDUPILOT_BIN}/libarducopter-heli.a”)
    target_link_libraries(${elf_file} “${ARDUPILOT_LIB}/libArduCopter_libs.a”)

Hello Juergen! Nice to see someone else using the ESP32 for Ardupilot! Im having trouble getting the I2C devices to work and i see you used the same MPU that i have, would you mind sharing your libraries/AP_HAL_ESP32/boards/esp32famos1.h file so i could see how you got it working?

Hello Lucas,
these settings I use for I2C and IMU inside my “esp32famos1.h”.
I am using the standard I2C pins of the ESP32 DEV Module

//Inertial sensors
#define HAL_INS_DEFAULT HAL_INS_MPU6050_I2C
#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args))
#define HAL_INS_PROBE_LIST PROBE_IMU_I2C(Invensense, 0, 0x68, ROTATION_NONE)

//I2C Buses
#define HAL_ESP32_I2C_BUSES {.port=I2C_NUM_0, .sda=GPIO_NUM_21, .scl=GPIO_NUM_22, .speed=400*KHZ, .internal=true}

Amazing, it’s working now, thanks a lot!

Hello All,
It’s been a while since I wrote here about what I’ve “learned”, but I haven’t been idle.

Inspired by questions in the forum about the function of motor drivers “Brushed With Relay”, I wanted to simulate this with my ESP32 FC.

At that time in September, however, there was no “GPIO” functionality for the Ardupilot ESP32 platform. So I had to implement this for myself first. A task to get deeper into Ardupilot development.

At this point, however, I must make it clear that this functionality was also implemented by the Ardupilot development team at almost the same time and that this development has a lot in common with my purely local development. This official version on the server is therefore not the result of my learning success. I don’t want to take credit for anything wrong.

I’m not repeating all of my code lines here, just the procedure of my development.

First, I copied the GPIO.cpp and GPIO.h files from the AP_HAL_EMPTY directory to the AP_HAL_ESP32 directory. Then the terms “Empty” had to be replaced with “ESP32” in all occurrences in both files. After that I added a test output like this to each empty function in the GPIO.cpp file
“gcs().send_text(MAV_SEVERITY_DEBUG, “GPIO::gpio_by_pin_num(pin(%d)) \n”, pin_num)”);
to see if and when the respective function was called with which parameters.
Compiling the corresponding firmware worked but there was no reaction in the MP messages window. Here I had hoped to at least see the GPIO::GPIO() or GPIO::init().
But OK, in my call to one of the functions in the BOARDS/esp32famos1.h there is no reference to any “GPIOs” and I didn’t want to use the RCOUT at first so as not to disrupt the corresponding function. My ESP32 board still has a few unused GPIO pins that are good for my function. So I first defined a new definition in BOARDS/esp32famos1.h
#define HAL_ESP32_GPIO {GPIO_NUM_4, GPIO_NUM_2}
I then adopted this definition for my GPIO.cpp, analogous to the example in RCOutput.cpp. A new firmware was quickly created and loaded, but there were still no messages from the functions.
OK again. Next step: my virtual rover doesn’t use GPIO yet. So I first defined a RELAY1_FUNCTION = 1 (relay) via MissionPlanner and manually set RELAY1_PIN = 4. Manually ‘4’ because this corresponds to my ESP32 pin. The predefined Ardupilot pins don’t work, of course. This refers to the Chibios platforms. And I set my RC channel 5 as the switching channel for the GPIO. But this configuration didn’t work either. I haven’t noticed any reaction yet.
Now, what’s missing? The experienced Ardupilot developers could definitely help me now, ask a question in the forum and I’m sure the right idea will come quickly. But I wanted to solve it myself and learn. So I started and searched the existing source files looking for the clue. I then found it in the HAL_ESP_CLASS.cpp, among other things, where the various hardware drivers are loaded. I added my GPIO.h to the “include” list and lo and behold, the next test firmware now shows a reaction. However, neither the GPIO::GPIO() nor the GPIO::init() were called, only GPIO::write() for each switching event triggered by the RC control.
Now it was just a simple task to introduce a check for valid pin numbers and to bring the functions write() read() toggle() to life.
My ESP32 Ardupilot platform now had 6 PWM outputs and 2 GPIOs and with this I could simulate the above mentioned function “Brushed With Relay” and “SKID Steering”.

In the last few days I wanted to tinker a bit with my ESP32 FC. I’m currently interested in whether it can also work with scripts.
Because it’s always recommended here to update to the latest Ardupilot, I upgraded my development environment to version 4.6. Unfortunately, I’m not a Linux expert and am therefore glad that others here have written scripts that also set up the development environment. This worked well initially. But now with the upgrade there were more problems than expected. The scripts also want to upgrade the ESP_IDF to version 5.3. This worked after several laborious attempts. I had to follow the relevant instructions meticulously. After a day and a half, the development environment was running and I was able to compile the firmware for the ESP32. I was happy.
But when I installed the firmware on the FC, I noticed that the parameter list was not being read correctly when connecting to Mission Planner. After further analysis, I found that the FC resets periodically. After further analysis, I was able to determine that this was related to the I2C interface and that a WatchDogTimer reset had been carried out. At first I thought it was a hardware defect. After all, my kitchen table lab is not an ESD-protected workbench. To verify this, I created a test software that was independent of Ardupilot and the development environment to test the I2C and SPI interfaces with the Arduino IDE. This showed no anomalies.
So it is somewhere in the area of ​​my Ardupilot development environment and Ardupilot software. To get further here, I first went back to Ardupilot version 4.4 and laboriously turned the ESP_IDF back and, lo and behold, the ESP32 FC is running again.
So the rule should apply after all: “Don’t touch a running system”
Now I have to search through the thousands of folders and files for differences between the versions in terms of I2C behavior.
Has another ESP32 FC developer already successfully experimented with Ardupilot 4.6 and I2C?

Update Dec 14,2024
After now lot of theoretical learning I now realized my first real ArduPilot project.
A small in some kind unusal rover.
The ArduPilot system based on ESP32 with external SD-card and simple MPU6050. No other sensors up to now.
The rover a skidsteared tracked vehicle based on very old Lego Mindstorms.
The basic rover itself is using a real old LEGO RCX Controller. This controller is dreiving the three motors for the tracks and the manipulator. The communication between ArduPilot ESP32 and LEGO RCX is using a special IR-interface. Simply only one 8 bit value is send from ESP32 to LEGO RCX secured by a propritary LEGO RCX protocol.
As first I am using onl manual mode an command the system with my also old Futaba RC system.
With this setup I have just a small ArduPilot testplatform for a very very small budget.



3 Likes

Update Dec 20,
now that the rover with ESP32 based FC basically works in manual mode, the SBus remote control signals are received by the FC and transmitted to the HW via an IR interface in LEGO RCX format, now comes another step towards automation of my learning curve.

Integration of a Holybro M10 mini GPS receiver.
After establishing the HW connection, my FC persistently showed NO GPS. To make sure that the HW is correct, I flashed my own simple firmware onto the controller and was able to see immediately that the GPS receiver delivers NMEA data at 115200 baud.
I defined the following via the board definition:

#define HAL_ESP32_UART_DEVICES \
{.port=UART_NUM_0, .rx=GPIO_NUM_3 , .tx=GPIO_NUM_1 },\
{.port=UART_NUM_1, .rx=GPIO_NUM_16, .tx=GPIO_NUM_17}

UART_NUM_0 is the FC USB port and UART_NUM_1 is the GPS port.
In general, the ESP32 has three possible UART HW interfaces
So the serial interfaces were checked using Mission Planner:
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,57
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,2
SERIAL2_BAUD,230
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,5
Since I only defined two interfaces above, I assumed UART_NUM_1 corresponds to SERIAL1, so

settings changed to:
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,115
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,5
SERIAL2_BAUD,230
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,-1
After it was said several times here in the forum, for To use the high baud rate 230400 in UBlox GPS and to allow auto-configuration, I also tried this:
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,230
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,5
SERIAL2_BAUD,230
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,-1
without success.
Shortly before I despaired, the ESP32 firmware might not support GPS at all, so I came up with the idea of ​​trying the other SERIAL_X interfaces.
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,230
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,5
SERIAL2_BAUD,230
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,-1
SERIAL3_BAUD,115
SERIAL3_OPTIONS,0
SERIAL3_PROTOCOL,5
Now the display in Mission Planner changed:
GPS: NO GPS and GPS2: NO FIX.
Now I changed to
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,230
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,-1
SERIAL2_BAUD,230
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,-1
SERIAL3_BAUD,115
SERIAL3_OPTIONS,0
SERIAL3_PROTOCOL,5
now got the message GPS: NO FIX which simply means
UART_NUM_1 from the board config file is SERIAL3
After that I tested also outside and got GPS: FIX

Has anyone from the ESP32 developers @DavidBuzz @Leon90 @skimans noticed something like this?

I think it’s mentioned here in the discussion:

1 Like

Thanks for the information.
At the moment I am not working not on the last ardupilot branch as I am stick on the older esp-idf. Maybe I have to update this shortly

Update Jan2025, 21th
Now GPS ist running and also I got the compass IST8310 of the Molybro M10mini working on I2C bus. Now the MPU6050 and the IST8310 are working on the same bus.
Next step that I tried was to run the rover outside with 3D-fix with an auto mission. But still no sucess.
If I switch to auto mode I only get the response that mode change is not possible. It seems that the Ardupilot ESP32 don’t store the mission but I am not sure. I disconnected and stopped mission planner after creating waypoints and than restart mission planner and reconnect to the FC I cannot download / verify the waypoints from the FC.
Does someone can tell me if auto missions are in general working on Ardupilot ESP32 or not.

1 Like