Thank you @DavidBuzz it’s ana amazing work you guys have been doing.
i did upload ardupilot on esp32devkit using your esp32buzz header. every thing went well until i got the “main loop 143<400hz” error on MissionPlanner. so i though i could try an esp32s3.
using both esp32s3empty and esp32s3devkit, everything flashes fine, but missionPlanner can connect. i think it looks stuck.
Could you perhaps point me on the right track to solve this issue.?
thanks a lot.
Hey @copilot , same thing happened to me with esp32 ( 143 < 400 Hz, main loop too slow) , then moved to esp32s3, and i can’t get any telemetry going. have you been successful so far?
I also could not get the S3 to work so went back to the normal esp32 version. Playing with the scheduler priorities I managed to increase the loop rate a bit. If I remember correctly it was getting close to 200Hz, that was some weeks ago and I have not tried it again since. Have you looked at the ArduPilot Discord ESP32 channel, there are also some more discussions and information.
Hi Chris & all the members,
I am having trouble connecting to GCS (mission planner/qgc/mavproxy) over tcp: 192.168.4.1 port:5760).
My setup:
esp32wroom32 + gy-91
followed the esp32 buzz build instructions and flashed it.
no sd card, nothing else is connected (i’am just testing the ardupilot firmware)
mission planner:
it connects but takes too long to load the parameters, also all the parameter are not able to load, can’t see any movement in HUD.
QGC:
Connects and disconnects automatically.
Mavproxy:
biren@biren:~$ mavproxy.py --master=tcp:192.168.4.1:5760
Connect tcp:192.168.4.1:5760 source_system=255
Log Directory:
Telemetry log: mav.tlog
Waiting for heartbeat from tcp:192.168.4.1:5760
MAV> Detected vehicle 1:1 on link 0
online system 1
STABILIZE> Mode STABILIZE
AP: ArduCopter V4.6.0-dev (5a54d9a2)
AP: esp32-buzz 10 6 1C A6 DC F4
AP: IMU0: fast sampling enabled 8.0kHz/1.0kHz
AP: Frame: UNSUPPORTED
PYR_ID$72_ID73_IDTACC_ID72_ID73_IDFAST_SAMP;WEK3_wFUNCTIO1AP: ArduCopter V4.6.0-dev (5a54d9a2)
AP: esp32-buzz 10 6 1C A6 DC F4
AP: IMU0: fast sampling enabled 8.0kHz/1.0kHz
AP: Frame: UNSUPPORTED
fence breach
Received 889 parameters (ftp)
Saved 889 parameters to mav.parm
AP: EKF3 IMU0 forced reset
AP: EKF3 IMU0 initialised
AP: PreArm: Motors: Check frame class and type
AP: EKF3 IMU0 tilt alignment complete
no link
link 1 down
no link
AP: PreArm: Motors: Check frame class and type
no link
no link
no link
?vno link
STABILIZE> no link
link 1 OK
heartbeat OK
STABILIZE> AP: PreArm: Motors: Check frame class and type
STABILIZE> no link
link 1 down
link 1 OK
heartbeat OK
no link
link 1 down
no link
link 1 OK
heartbeat OK
so you figured it was the missing SD card. Seems to work fine?
are you able to connect through MP with tcp without any disconnection and slow parameter loading?
How could having SD card solve the problem?
Is there any way i can get it to work without SD card?
disable scripting while building the firmware?
additionally if one could point me in right direction, i will try to debug the issue.
Hi Birendra,
I use UDP connection and have disabled SD card (I plan to use it one day). That works like a dream. To me it looks like the connection is not really stable. Can you try with UDP?
Cheers,
Christian
Hi,
Thanks for your reply, UDP works flawlessly, I just wanted to use TCP because it is more reliable.
Now I have some more issues which is already mentioned by David Buzz.
Main loop is slow (120HZ < 400HZ).
Hello, are there a maximum of two UART ports or has anyone gotten all three to work? I only get (uart0 gpio1 and gpio3) and (uart1 gpio16 gpio17) to work, unfortunately uart2 gpio9 gpio10 gives an error. Everything else works great, gyro, baro, compass, GPS.
@uwe_dallinger Uart0 not work. Uart0 is for USB cable connection.
@uwe_dallinger
Which AP_HAL_ESP32/boards/ ???.h hardware definition file are you using? Is it one of the predefined boards or did you use your own custom board?
Yes, it is used for USB to Serial, so it works. But if you define uart2 gpio9 gpio10, the ESP32 may not boot. I have gotten it to boot sometimes, but with no functionality on that port.
I’m playing with this configuration and everything works except UART2. I thought maybe someone found a way to make it work.
/*
- 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-----
// Not recognized
//#define AP_COMPASS_AK8963_ENABLED TRUE
//#define HAL_MAG_PROBE_LIST PROBE_MAG_IMU(AK8963, mpu9250, 0, ROTATION_NONE) // Default
// Check I2C PORT and enable flag when adding external I2C Compass
#define AP_COMPASS_QMC5883L_ENABLED TRUE
#define HAL_MAG_PROBE_LIST PROBE_MAG_I2C(QMC5883L, 0, 0x0D,true , ROTATION_NONE)
#define HAL_PROBE_EXTERNAL_I2C_COMPASSES 1
#define ALLOW_ARM_NO_COMPASS 1
// -----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 0
#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
//#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2 //D UART2
//#define DEFAULT_SERIAL2_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 //57600
//#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS //B UART1: GPS1
//#define DEFAULT_SERIAL3_BAUD AP_SERIALMANAGER_GPS_BAUD/1000 //57600, Can not define default baudrate here (by config only)
// ------------------------------------------------------------------
// 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 1
// 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 57
// 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 }
//#define HAL_ESP32_RCOUT { GPIO_NUM_25,GPIO_NUM_27, GPIO_NUM_33, GPIO_NUM_32, GPIO_NUM_13, GPIO_NUM_12, GPIO_NUM_26, GPIO_NUM_15, GPIO_NUM_8, GPIO_NUM_7}
// ------------------------------------------------------------------------------------
// 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=1MHZ, .hspeed=1MHZ},
{.name=“mpu9250”, .bus=0, .device=1, .cs=GPIO_NUM_5, .mode = 0, .lspeed=2MHZ, .hspeed=8MHZ}
// ------------------------------------------------------------------------------------
//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}
//{.port=UART_NUM_2, .rx=GPIO_NUM_9, .tx=GPIO_NUM_10}
// ------------------------------------------------------------------------------------
//#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
On my ESP32 Dev board the GPIOs 6 to 11 are resevered and used for internal FLASH. As ardupilot needs the FLASH it isn’t possible to use the UART on these GPIOs
I used this pinout diagram and thought I could use GPIO 9 and 10. Other diagrams clearly mention that these pins are for flash only. I should have researched a little more, so there is no UART2 available for this board.
As the ESP32 is working like other actual controller you can route the UARTS to different GPIO not only as shown in the picture.
So you can try other free GPIO. But I didn’t tested it yet as I don’t have the need of more UART at the moment. What do you want to use the UARTs for?
UART1 is used for GPS and UART2 should become a MAVLink2 connection.
I just double checked the EXPRESS ESP32 documentation and I don’t found any information that UART1 has to be routed to GPIO9 / GPIO10. This is only the default information. As I said any other free digital GPIO can be used.
Hi, Could you plz share the compiled firmware to me, pretty excited to try !
hi, can you share with me the complied file?
email: amirumair70@gmail.com
shaksham00786@gmail.com, Done!
amirumair70@gmail.com, Done!