Building a mini drone use ESP32

I assume if DShot doesn’t work you go back to “standard” pwm?
Every modern ESC that supports DShot is also backwards compatible to normal pwm, so there’s no limitation.
I would recommend basically any BLHeli_32 or Bluejay-flashed BLHeli_S ESC

1 Like

Hello,

what a fantastic project and initiative! I would really like to contribute here. Well, maybe with some error logs first. I managed to compile the code for ESP32 and flashed it on my ESP32Dev v4. Worked like a charm. I then connected to the wifi accesspoint. Launched MP and tried to connect via tcp (192.168.4.1 on 5760 with 115200 baud rate).

Unfortunately, without success. MP gives me a timeout. I checked my firewall and disabled it (I’m running on Ubuntu). Still no success.

The tcp seems to be there:

telnet 192.168.4.1 5760

Trying 192.168.4.1...
Connected to 192.168.4.1.
Escape character is '^]'.

This is what ninja monitor gives me:

Anyone knows what is going on? I have no SD-Card reader attached. Could this be the culprit?

Oh and as for the sensors: I use MPU9250 and BMP280 on SPI …

rst:0x1 (POWERON_RESET),boot:0x1a (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:1
load:0x3fff0030,len:4976
load:0x40078000,len:15300
ho 0 tail 12 room 4
load:0x40080400,len:3776
entry 0x40080620
I (559) cpu_start: Multicore app
I (559) cpu_start: Pro cpu up.
I (560) cpu_start: Starting app cpu, entry point is 0x40085698
I (0) cpu_start: App cpu up.
I (577) cpu_start: Pro cpu start user code
I (577) cpu_start: cpu freq: 240000000
I (577) cpu_start: Application information:
I (582) cpu_start: ELF file SHA256:  871207bb39df5054...
I (588) cpu_start: ESP-IDF:          v4.4.6-502-g6897e4e0fa
I (594) cpu_start: Min chip rev:     v0.0
I (599) cpu_start: Max chip rev:     v3.99 
I (604) cpu_start: Chip rev:         v3.0
I (609) heap_init: Initializing. RAM available for dynamic allocation:
I (616) heap_init: At 3FFAE6E0 len 00001920 (6 KiB): DRAM
I (622) heap_init: At 3FFC6508 len 00019AF8 (102 KiB): DRAM
I (628) heap_init: At 3FFE0440 len 00003AE0 (14 KiB): D/IRAM
I (634) heap_init: At 3FFE4350 len 0001BCB0 (111 KiB): D/IRAM
I (641) heap_init: At 40096508 len 00009AF8 (38 KiB): IRAM
I (648) spi_flash: detected chip: generic
I (652) spi_flash: flash io: qio
I (667) esp_core_dump_uart: Init core dump to UART
I (667) cpu_start: Starting scheduler on PRO CPU.
I (0) cpu_start: Starting scheduler on APP CPU.
virtual void ESP32::Scheduler::init():70 running with CONFIG_FREERTOS_HZ=500
OK created task _main_thread
AnalogIn: eFuse Two Point: NOT supported
AnalogIn: eFuse Vref: Supported
OK created task _timer_thread
oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo
OK created task _rcout_thread
RCOե�}ѡɕ��5
OK created task _uart_thread
Mounting sd 
I (757) SD...: Initializing SD card as SDMMC


Init ArduCopter V4.5.0-dev (00a65632)

Free RAM: 110592
OK created task _io_thread
OK created task _storage_thread
Firmware change: erasing EEPROM...
done.
E (785) sdmmc_common: sdmmc_init_ocr: send_op_cond (1) returned 0x107
E (785) vfs_fat_sdmmc: sdmmc_card_init failed (0x107).
sdcard is not mounted
load_all took 2399174us
I (3183) wifi:wifi driver task: 3ffd9800, prio:23, stack:6656, core=0
I (3183) system_api: Base MAC address is not set
I (3183) system_api: read default base MAC address from EFUSE
I (3189) wifi:wifi firmware version: 1fd20f4
I (3193) wifi:wifi certification version: v7.0
I (3197) wifi:config NVS flash: disabled
I (3201) wifi:config nano formating: disabled
I (3205) wifi:Init data frame dynamic rx buffer num: 16
I (3211) wifi:Init static rx mgmt buffer num: 5
I (3215) wifi:Init management short buffer num: 32
I (3219) wifi:Init dynamic tx buffer num: 16
I (3223) wifi:Init static rx buffer size: 1600
I (3227) wifi:Init static rx buffer num: 2
I (3231) wifi:Init dynamic rx buffer num: 16
I (3235) wifi_init: tcpip mbox: 32
I (3239) wifi_init: udp mbox: 6
I (3243) wifi_init: tcp mbox: 6
I (3247) wifi_init: tcp tx win: 5744
I (3251) wifi_init: tcp rx win: 5744
I (3255) wifi_init: tcp mss: 1436
I (3259) wifi_init: WiFi RX IRAM OP enabled
I (3419) phy_init: phy_version 4791,2c4672b,Dec 20 2023,16:06:06
I (3493) wifi:mode : softAP (aa:42:e3:48:f7:0c)
I (3495) wifi:Total power save buffer number: 8
I (3495) wifi:Init max length of beacon: 752/752
I (3495) wifi:Init max length of beacon: 752/752
OK created task _wifi_thread
AnalogIn: adding ardupin:255-> which is adc1_offset:-1
AnalogIn: channel:0 created but using delayed adc and gpio pin configuration
spi device constructed SPI:bmp280:0:0
No Compass backends available
spi device constructed SPI:mpu9250:0:1
Init GyroI (17249) wifi:new:<1,1>, old:<1,1>, ap:<1,1>, sta:<255,255>, prof:1
I (17249) wifi:station: 52:02:7b:0d:a0:db join, AID=1, bgn, 40U
I (17547) esp_netif_lwip: DHCP server assigned IP to a station, IP is: 192.168.4.2

I am not sure may I understand correct that you try to connect to 192.168.4.1
But your ESP32 seems to be assigned to 192.168.4.2 while 192.168.4.1 is your access point.

1 Like

The ESP creates an AP on 192.168.4.1. The IP address, which appears in the monitor logs (192.168.4.2) is from my connection of my laptop (I join the Wifi, created by the ESP32).

Interestingly, I got it working a couple of minutes ago and the drone appeared in MP, but I couldn’t replicate. Could it be a faulty sensor?

Update on my build: I figured it was the missing SD card. Seems to work fine now. I’m able to connect through MP with tcp. Thanks @Leon90 for details you provided above. That helped a lot to get started!!

Hi @cmb87 greetings, how to upload that three file bootloader.bin,ardupilot.bin , partition_table.bin using espressif flash tool.
because I am using the windows 11. and I successful completed compiling process.

@Leon90 Thank you esp32 porting, I am stuck uploading step. cloud you please tell me how to upload that three file.

bootloader.bin,ardupilot.bin , partition_table.bin

using espressif flash tool
because I am using the windows 11. and I successful completed compiling process.

I used the essprif-sdk under Ubuntu (you find all the instructions in the README.md in AP_HAL_ESP32 dir). As I’m not a Windows guy, some suggestions:

Under Windows 11 install Docker ( Install Docker Desktop on Windows | Docker Docs) and spin up an Ubuntu container. Volume mount your ardupilot repo and usb ports to that container and use
./waf copter --upload

Hope that helps. Good luck.

Thank you for your reply, Mr. Chris P. I hope this will be helpful. Let me work on this and tell you the result.

Hello, @Leon90 any chance to send me the files for rover version to test a project? Thank you in advance . jb132_yo@yahoo.com

Is it working for Rover? I thought so far Copter is only supported?

Thanks guys! This is a really great way to get a cheap Ardupilot compatible controller that you can build yourself and experiment with. It definitely prompted me to also delve deeper into the Ardupilot code to understand, experiment and play with it some more.
Being inspired by @Leon90 and having all the parts (SDCard breakout, MPU9250 and BMP280) laying around, I also gave it a try. Setting up the build environment (on Ubuntu) was straight forward by following the steps at ardupilot/libraries/AP_HAL_ESP32/README.md at master · ArduPilot/ardupilot · GitHub then using the esp32buzz board as target. The master version was 4.6.0-dev

The ESP32 and peripheral was built on a breadboard and firmware flashed using the instructions in the previously mentioned readme file. So far everything seems to work. I managed to connect both via WiFi and using an UART to USB bridge. Using an oscilloscope I probed the motor output pins while doing a motor test in MP and it also seems to work fine, why wouldn’t it :wink:

Anyway, the only thing that worries me at the moment is that MP reports “Main loop slow (132Hz < 400Hz)”.
Is this too slow for proper control? What would the minimum be for Copter?
Leon90 also mentioned that he was concerned about the main loop speed, does anybody have some advice on which features could safely be disabled to improve the rate?

1 Like

Have anybody tried and had success the ESP32-S3?
I gave it (esp32s3devkit) a quick try last night, startup seems fine but telemetry then freezes shortly after the first MAVLink messages appear. Also found a possible bug (related to S3) in RmtSigReader.cpp, in the init() function RMT_CHANNEL_6 should be used as RX only works on channels 4 to 7.
Will give it another shot tonight.

The reason for trying the S3 is to see if it would help solve the slow main loop problem. It seems the problem with ESP32 is not the CPU clock speed but the bus speed at which instructions can be fetched from the external flash. The S3 has the same CPU clock speed but a faster bus and better cache which could allow faster execution. Any thoughts on this?

Please drop your email bro…I want some help related to your project.

Hey all… I’m the “buzz” refered to in the “esp32buzz” board above, and I’ve been hacking on ardupilot on esp32 for a few years…[i didnt start it, I just got involved very early] its experimental, and although I’ve seen a couple copter fly on esp32, its much easier to fail on esp32 than on stm32, so if u just want to “go fly”, any of the cheap stm32 boards are much easier.
tips:
1 - If you get “slow loop rate” - the FreeRTOS scheduler is much worse than chibios, and this is the biggest weakness … even if u get everything else working, its hard to get the scheduler over 150hz… which is just-barely enough to get a copter to fly. [planes will fly at 50hz].
2 - If you’ve flashed a board and MissionPlanner wont connect to it, then this is REALLY common, and usually means you dont have a sensor connected, or dont have it connected right, or connected the way the software expects. SPI and I2C are very different, bus rates, pinouts, uncommon sensor, etc. Mission-Planner definitely won’t connect unless everything-else is working, and even then, sometimes still wont.
3 - “binary garbage” on the serial console after boot.? that’s called “mavlink” and can be a good sign… it means mission-planner might connect over your USB link (this depends on if u have the parameters set to allow this or not ).
4 - cant upload…? The esp32 has a sequence of steps it goes through to get into boot-loader mode and be programmable, which doesn’t always work automatically…if its not working for you… try long-holding the “boot” button while you poweron (or while you briefly press the reset button), this pretty-much guarentees it will go into bootloader mode and u can then upload/flash it.
5 - is the SD-card required…? no, not to boot.
6 - is the imu required.? yes, absolutely… except for the ‘esp32s3empty’ board that fakes its own imu, but this only flashes onto esp32-s3 board/s which are even-more-experimental than normal ‘esp32’.
7 - supported boards…? No manufacturer has released ready-to-go boards for this, so its all diy , one-off, so that also makes it quite a bit harder.
8 - esp32 and esp32s3 are the only supported target types, as both of these are dual-core, and generally considered powerful-enough-just to do this… single-cpu variants might be made to work if u disabled their wifi entirely… but probably not.
9 - experimental, got it. :slight_smile:

4 Likes

Oh, and if u find a fix for something that’s clearly broken in ESP32 or ESP32S3, i’m always interested!.. open a PR at Pull requests · ArduPilot/ardupilot · GitHub , mention ‘esp32’ and my-name as well, and if it fixes a real issue without breaking anything else, we’ll try to get it merged.

I have never try for rover vehicle.

I only do sone try for copter, but i think it will be work better for rover, rover require lower loop speed.

You can send msg here for me.

Yea, after a upgrade I also got it compiled for Rover. Super nice :). I’m however stuck with the compass. I use a MPU9250, the blue one. The gyro and accel are recognized but the onboard compass isn’t, although I got bad compass health message. In MP I cannot find the compass in HWID. Interestingly MP also tells me the gyro+accel is a MPU6000… How, did it work for you? Below my config for ESP32 DEVKIT 4. Maybe it is also helpful for somebody else…

/*
 * 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 HAL_ESP32_BOARD_NAME "esp32-devv4"

// make sensor selection clearer
#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args))
#define PROBE_IMU_SPI(driver, devname, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,hal.spi->get_device(devname),##args))
#define PROBE_IMU_SPI2(driver, devname1, devname2, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,hal.spi->get_device(devname1),hal.spi->get_device(devname2),##args))

#define PROBE_BARO_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_Baro_ ## driver::probe(*this,std::move(GET_I2C_DEVICE(bus, addr)),##args))
#define PROBE_BARO_SPI(driver, devname, args ...) ADD_BACKEND(AP_Baro_ ## driver::probe(*this,std::move(hal.spi->get_device(devname)),##args))

#define PROBE_MAG_I2C(driver, bus, addr, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe(GET_I2C_DEVICE(bus, addr),##args))
#define PROBE_MAG_SPI(driver, devname, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe(hal.spi->get_device(devname),##args))
#define PROBE_MAG_IMU(driver, imudev, imu_instance, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe_ ## imudev(imu_instance,##args))
#define PROBE_MAG_IMU_I2C(driver, imudev, bus, addr, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe_ ## imudev(GET_I2C_DEVICE(bus,addr),##args))

//------------------------------------


//-----INS/IMU-----
#define HAL_INS_DEFAULT HAL_INS_MPU9250_SPI
#define HAL_INS_MPU9250_NAME "mpu9250"
#define HAL_INS_PROBE_LIST PROBE_IMU_SPI( Invensense, HAL_INS_MPU9250_NAME, ROTATION_NONE)


//-----COMPASS-----
#define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE)
//#define HAL_MAG_PROBE_LIST PROBE_MAG_I2C(QMC5883L, 1, 0x0d,true ,  ROTATION_NONE)
//#define HAL_PROBE_EXTERNAL_I2C_COMPASSES 1
#define HAL_PROBE_EXTERNAL_I2C_COMPASSES 

#define ALLOW_ARM_NO_COMPASS				1
#define AP_COMPASS_AK8963_ENABLED TRUE

// -----BARO-----
#define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
#define HAL_BARO_BMP280_NAME "BMP280"
#define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(BMP280, "bmp280")
// allow boot without a baro
#define HAL_BARO_ALLOW_INIT_NO_BARO 1


// -----no airspeed sensor-----
#define AP_AIRSPEED_MS4525_ENABLED 0
#define AP_AIRSPEED_ENABLED 0
#define AP_AIRSPEED_ANALOG_ENABLED 0
#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0

// -----ADC -----
// ADC is available on lots of pints on the esp32, but adc2 cant co-exist with wifi we choose to allow ADC on :
//#define HAL_DISABLE_ADC_DRIVER 1
#define TRUE 1
#define HAL_USE_ADC TRUE

// the pin number, the gain/multiplier associated with it, the ardupilot name for the pin in parameter/s.
//
// two different pin numbering schemes, both are ok, but only one at a time:
#define HAL_ESP32_ADC_PINS_OPTION1 {\
	{ADC1_GPIO35_CHANNEL, 11, 1},\
	{ADC1_GPIO34_CHANNEL, 11, 2},\
	{ADC1_GPIO39_CHANNEL, 11, 3},\
	{ADC1_GPIO36_CHANNEL, 11, 4}\
}
#define HAL_ESP32_ADC_PINS_OPTION2 {\
	{ADC1_GPIO35_CHANNEL, 11, 35},\
	{ADC1_GPIO34_CHANNEL, 11, 34},\
	{ADC1_GPIO39_CHANNEL, 11, 39},\
	{ADC1_GPIO36_CHANNEL, 11, 36}\
}
// pick one:
//#define HAL_ESP32_ADC_PINS HAL_ESP32_ADC_PINS_OPTION1
#define HAL_ESP32_ADC_PINS HAL_ESP32_ADC_PINS_OPTION2


// ------------------------------------------------------------------
// uncommenting one or more of these will give more console debug in certain areas.. ... 
// ...however all teh extra printf's use a lot of stack, so best to limit yourself to only uncommenting one at a time
//#define STORAGEDEBUG 1
//#define SCHEDDEBUG 1
//#define FSDEBUG 1
//#define BUSDEBUG 1 //ok
//#define WIFIDEBUG 1 //uses a lot?
//#define INS_TIMING_DEBUG 1 //define this to see all the imu-resets and temp resets and imu timing info on the console.

// 2 use udp, 1 use tcp...  for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 14550  tcp: 5760
#define HAL_ESP32_WIFI 2

// tip: if u are ok getting mavlink-over-tcp or mavlink-over-udp and want to disable mavlink-over-serial-usb
//then set ardupilot parameter SERIAL0_PROTOCOL = 0 and reboot.
// u also will/may want..
//LOG_BACKEND_TYPE 1
//LOG_DISARMED 1
//SERIAL0_PROTOCOL 0
//#define SERIAL1_PROTOCOL 5
//#define SERIAL1_BAUD 115


// 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_25,GPIO_NUM_27, GPIO_NUM_33, GPIO_NUM_32, GPIO_NUM_13, GPIO_NUM_12 }

// ------------------------------------------------------------------------------------
// SPI BUS setup, including gpio, dma, etc
// note... we use 'vspi' for the bmp280 and mpu9250
#define HAL_ESP32_SPI_BUSES \
    {.host=VSPI_HOST, .dma_ch=1, .mosi=GPIO_NUM_23, .miso=GPIO_NUM_19, .sclk=GPIO_NUM_18}
// tip:  VSPI_HOST  is an alternative name for esp's SPI3
//#define HAL_ESP32_SPI_BUSES {}


// SPI per-device setup, including speeds, etc.
#define HAL_ESP32_SPI_DEVICES \
    {.name= "bmp280", .bus=0, .device=0, .cs=GPIO_NUM_2, .mode = 3, .lspeed=1*MHZ, .hspeed=1*MHZ}, \
    {.name="mpu9250", .bus=0, .device=1, .cs=GPIO_NUM_5,  .mode = 0, .lspeed=2*MHZ, .hspeed=8*MHZ}

// ------------------------------------------------------------------------------------
//I2C bus list
#define HAL_ESP32_I2C_BUSES \
	{.port=I2C_NUM_0, .sda=GPIO_NUM_21, .scl=GPIO_NUM_22, .speed=400*KHZ, .internal=true}
//#define HAL_ESP32_I2C_BUSES {} // using this embty block appears to cause crashes?

// ------------------------------------------------------------------------------------
// rcin on what pin?
#define HAL_ESP32_RCIN GPIO_NUM_4

// ------------------------------------------------------------------------------------
//HARDWARE UARTS
#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 }



// ------------------------------------------------------------------------------------

//#define AP_FILESYSTEM_ESP32_ENABLED 1

// Do u want to use mmc or spi mode for the sd card, this is board specific ,
//  as mmc uses specific pins but is quicker,
// #define HAL_ESP32_SDMMC 0
// // and spi is more flexible pinouts....  dont forget vspi/hspi should be selected to NOT conflict with SPI_BUSES above
// //#define HAL_ESP32_SDSPI {.host=VSPI_HOST, .dma_ch=2, .mosi=GPIO_NUM_2, .miso=GPIO_NUM_15, .sclk=GPIO_NUM_14, .cs=GPIO_NUM_21}

// #define HAL_ESP32_SDCARD 0
// #define LOGGER_MAVLINK_SUPPORT 0
#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS"
#define HAL_BOARD_TERRAIN_DIRECTORY "/SDCARD/APM/TERRAIN"
#define HAL_BOARD_STORAGE_DIRECTORY "/SDCARD/APM/STORAGE"

// // this becomes the default value for the ardupilot param LOG_BACKEND_TYPE, which most ppl want to be 1, for log-to-flash
// // setting to 2 means log-over-mavlink to a companion computer etc.
// #define HAL_LOGGING_BACKENDS_DEFAULT 1

// ------------------------------------------------------------------------------------
#define HAL_ESP32_RMT_RX_PIN_NUMBER 4

1 Like