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.
Alternatively, the "./waf plane' build outputs a python command that y can cut-n-paste to flash... buzz found that but using that command with a slower baudrate of 921600 instead of its recommended 2000000 worked for him:
The ESP-IDF os is compiled as a library to the project.
First waf configure the esp-idf cmake and run a target to get all esp-idf includes.
Waf compile all ardupilot parts in libardusub.a and libArduSub_libs.a (for example for subs, but similarly for planes, copter, rover).
Then waf execute the esp-idf cmake to compile esp-idf itself.
And the cmake link the final ardupilot.elf against previous built libraries.
The ardupilot.elf contains all symbol. The cmake provide a stripped version as ardupilot.bin.
## Test hardware
Currently esp32 dev board with connected gy-91 10dof sensor board is supported. Pinout (consult UARTDriver.cpp and SPIDevice.cpp for reference):
### Uart connecion/s
Internally connected on most devboards, just for reference.
After flashing the esp32 , u can connect with a terminal app of your preference to the same COM port ( eg /dev/ttyUSB0) at a baud rate of 115200, software flow control, 8N1 common uart settings, and get to see the output from hal.console->printf("...") and other console messages.
2nd column is the ardupilot _PIN number and matches what u specify in the third column of HAL_ESP32_ADC_PINS #define elsewhere :
if HAL_ESP32_ADC_PINS == HAL_ESP32_ADC_PINS_OPTION1:
| ESP32 | AnalogIn |
| --- | --- |
| GPIO35 | 1 |
| GPIO34 | 2 |
| GPIO39 | 3 |
| GPIO36 | 4 |
| GND | GND |
eg, set ardupilot params like this:
RSSI_ANA_PIN = 3 - and it will attempt to read the adc value on GPIO39 for rssi data
BATT_CURR_PIN = 2 - and it will attempt to read the adc value on GPIO34 for battery current
BATT_VOLT_PIN = 1 - and it will attempt to read the adc value on GPIO35 for battery voltage
ARSPD_PIN = 4 - and it will attempt to read the adc value on GPIO36 for analog airspeed data
if HAL_ESP32_ADC_PINS == HAL_ESP32_ADC_PINS_OPTION2:
| ESP32 | AnalogIn |
| --- | --- |
| GPIO35 | 35 |
| GPIO34 | 34 |
| GPIO39 | 39 |
| GPIO36 | 36 |
| GND | GND |
eg, set ardupilot params like this:
RSSI_ANA_PIN = 39 - and it will attempt to read the adc value on GPIO39 for rssi data
BATT_CURR_PIN = 34 - and it will attempt to read the adc value on GPIO34 for battery current
BATT_VOLT_PIN = 35 - and it will attempt to read the adc value on GPIO35 for battery voltage
ARSPD_PIN = 36 - and it will attempt to read the adc value on GPIO36 for analog airspeed data
### RC Servo connection/s
| BuzzsPcbHeader|ESP32| RCOUT |TYPICAL |
| --- | --- | --- | --- |
| servo1 |PIN25|SERVO-OUT1|AILERON |
| servo2 |PIN27|SERVO-OUT2|ELEVATOR|
| servo3 |PIN33|SERVO-OUT3|THROTTLE|
| servo4 |PIN32|SERVO-OUT4| RUDDER |
| servo5 |PIN22|SERVO-OUT5| avail |
| servo6 |PIN21|SERVO-OUT6| avail |
If you don't get any PWM output on any/some/one of the pins while ardupilot is running, be sure you have set all of these params:
//ail
SERVO1_FUNCTION = 4
// ele
SERVO2_FUNCTION = 19
//thr
SERVO3_FUNCTION = 70
//rud
SERVO4_FUNCTION = 21
// for now make it a copy of ail, in case u have two ail servos and no Y lead
SERVO5_FUNCTION = 4
// for now make it a copy of ail,for testing etc.
SERVO6_FUNCTION = 4
// right now, we only have 6 channels of output due to pin limitations..
(If the RTC source is not required, then Pin12 32K_XP and Pin13 32K_XN can be used as digital GPIOs, so we do, and it works)
### GY-91 connection
This is how buzz has the GY91 wired ATM, but its probable that connecting external 3.3V supply to the VIN is better than connecting a 5V supply, and then the 3V3 pin on the sensor board can be left disconnected, as it's actually 3.3v out from the LDO onboard.
|ESP32|GY-91|
|---|---|
|GND|GND|
|5V|VIN|
|3.3V|3V3|
|IO5|NCS|
|IO23|SDA|
|IO19|SDO/SAO|
|IO18|SCL|
|IO26|CSB|
## debugger connection
Currently used debugger is called a 'TIAO USB Multi Protocol Adapter' which is a red PCB with a bunch of jtag headers on it and doesn't cost too much. https://www.amazon.com/TIAO-Multi-Protocol-Adapter-JTAG-Serial/dp/B0156ML5LY
|ESP32| 20PINJTAG|
| --- | --- |
|D12 | TDI(PIN5)|
|D13 | SWCLK/TCLK(PIN9)|
|D14 | SWDIO/TMS(PIN7)|
|D15 | SWO/TDO(PIN13)|
|3.3v | -- ( powered via usb, not programmer, or PIN1)|
|GND | GND(any of PIN4,PIN6,or PIN8 , all GND)|
|EN | TRST(PIN3)|
## SDCARD connection
|ESP32| SDCARD |
| --- | --- |
|D2 | D0/PIN7 |
|D14 | CLK/PIN5 |
|D15 | CMD/PIN2 |
|GND | Vss1/PIN3 and Vss2/PIN6 |
|3.3v | Vcc/PIN4 |
## Current progress
### Main tasks
- [x] Build system
- [x] Scheduler and semaphores
- [x] SPI driver
- [x] WiFi driver ( connect with MissionPlanner or mavproxy on TCP to host: 192.168.4.1 and port: 5760 )
- [x] Uart driver ( non-mavlink console messages and ardupilot Serial0 with mavlink or gps )
- [X] RCIN driver ( PPMSUM INPUT on GPIO4 )
- [X] GPS testing/integration ( Serial ublox GPS, as ardupilot SERIAL0 on RX2/TX2 aka GPIO16 and GPIO17 )
- [X] PWM output driver
- [x] RCOUT driver ( 4 channels working right now)
- [x] I2C driver
- [x] Storage
- [X] OTA update of the fw
- [X] SdCard
- [x] Mavlink on console/usb as well as wifi.
- [x] UDP mavlink over wifi
- [x] TCP mavlink over wifi (choose tcp or udp at compile time , not both)
- [x] parameter storage in a esp32 flash partition area
- [x] Custom boards build
- [x] Perfomance optimization
- [x] SdCard mounts but ardupilot logging to SD does not
- [x] waf can upload to your board with --upload now
- [X] PWM output driver works, but it appears that throttle supression when disarmed does not.
- [X] AnalogIn driver - partial progress not really tested or documented
- [X] Finish waf commands to build seamlessly and wrap all function of esp-idf without command voodoo
### Known Bugs
- [ ] slow but functional wifi implementation for tcp & udp.
### Future development
- [ ] Automatic board header listing
- [ ] UDP mavlink over wifi does not automatically stream to client/s when they connect to wifi AP.
- [ ] Fix parameters loading in wifi both udp and tcp (slow and not reliable)
- [ ] Pin remapping via parameters
- [ ] GPIO driver
- [ ] DShot driver
- [ ] 4way pass
- [ ] esc telemetry
- [ ] ws2812b ws2815 led strip
- [ ] INA219 driver
- [ ] GSD
- [ ] Buzzer
### analysing a 'coredump' from the uart...
Save the log where coredump appears to a file, i'll call it core.txt