madflight

0

ESP32 / RP2040 / STM32 Arduino Flight Controller

Miscellaneous

rp2040
stm32
flight-controller
esp32

Manless Aerial Device

This is an Arduino library to build ESP32 / ESP32-S3 / RP2350 / RP2040 / STM32 flight controllers. A functional DIY flight controller can be build for under $10 from readily available development boards and sensor breakout boards. Ideal if you want to try out new flight control concepts, without first having to setup a build environment and without having to read through thousands lines of code to find the spot where you want to change something.

Quadcopter.ino is a 1000 line demo program for a quadcopter. It has been flight tested on ESP32, ESP32-S3, RP2040, and STM32F405 microcontrollers with the Arduino IDE. The program can be easily adapted to control your plane or VTOL craft. The source code has extensive documentation explaning what the settings and functions do.

Feedback is Welcome

I enjoy hacking with electronics and I'm attempting to write some decent code for this project. If you enjoy it as well, please leave some feedback in the form of Stars, Issues, Pull Requests, or Discussions. Thanks!

Documentation

For full documention see madflight.com and the source code itself.

Quick Start

Required Hardware
Getting Started
Safety First
ESP32 / ESP32-S3 Setup and Pinout
RP2350 / RP2040 Setup and Pinout
STM32 Setup and Pinout
Connecting the IMU Sensor
Software Design
Changes from dRehmFlight
Flight Controllers on Github
Disclaimer

Required Hardware

  • Development board:
    • RP2350 RP2040 (e.g. Raspberry Pi Pico 2)
    • or ESP32/ESP32-S3 (e.g. Espressiv DevKitC)
    • or STM32 (e.g. Black Pill or a commercial flight controller)
  • SPI IMU sensor (BMI270, MPU9250, MP6500, or MPU6000), if not available then use an I2C IMU sensor (MPU6050 or MPU9150)
  • RC Receiver: ELRS, CRSF, SBUS, DMSX, or PPM
  • BEC or DC-DC converter to power your board from a battery
  • ESC (OneShot125 or 50-490Hz PWM) and/or servos (50-490Hz PWM)

Optional Hardware

  • GPS Module (Serial)
  • Barometer (I2C BMP280, MS5611)
  • Magnetometer (I2C QMC5883L)
  • Current/Voltage Sensor (ADC or I2C INA226)
  • Optical Flow Sensor (I2C)

Getting Started

  1. Install the Arduino madflight library
  2. Open example Quadcopter.ino in the Arduino IDE.
  3. Setup the USER-SPECIFIED DEFINES section
  4. If you're not using a default pinout (see below) then setup your board pinout in the BOARD section.
  5. Connect your IMU (gyro/acceleration) sensor as shown below.
  6. Upload Quadcopter.ino to your board. Connect the Serial Monitor at 115200 baud and check the messages. Type help to see the available CLI commands.
  7. Use CLI print commands like pimu, pgyro, proll to Check that IMU sensor and AHRS are working correctly.
  8. IMPORTANT: Use CLI calimu and calmag to calibate the sensors.
  9. Connect radio receiver to your development board according to the configured pins.
  10. Review the RC RECEIVER CONFIG section. Either match you RC equipment to the settings, or change the settings to match your RC equipment.
  11. Check your radio setup: Use CLI ppwm and pradio to show pwm and scaled radio values.
  12. Connect motors (no props) and battery and check that motor outputs are working correctly. For debugging, use CLI pmot to show motor output.
  13. Mount props, go to an wide open space, and FLY!

Safety First!!!

By default madflight has these safety features enabled:

  • Motors only rotate when armed.
  • Arming Procedure: set throttle low then flip the arm switch from disarmed to armed.
  • Kill Switch: when the arm switch is in the disarm position, disarm and stop motors until re-armed.
  • Failsafe: when radio connection is lost, disarm and stop motors until re-armed.
  • Armed Low Throttle: motors run at low speed, to give visible armed indication.
  • LED armed/disarmed indicator.

ESP32 / ESP32-S3 Setup and Pinout

madflight works with Arduino-ESP32 v3.x.x

madflight v1.1.2 and earlier works with Arduino-ESP32 v2.x.x

Dual Core / FPU / FreeRTOS

ESP32 and ESP32-S3 have dual core CPU, but single core FPU. ESP-IDF implementation limits float usage to a single core, and float can not be used in interrupts. FreeRTOS is always enabled and a watchdog limits interrupt execution time.

madflight uses float and is therefor limited to single core operation. The IMU loop runs as a high priorty task, triggered by the IMU interrupt.

I2C

Arduino-ESP32 v2.0.17 has an I2C bug which causes the bus to hang for 1 second after a failed read, which can happen a couple times per minute. This makes Wire I2C for IMU not a real option...

A workaround is to use #define USE_ESP32_SOFTWIRE which enables software I2C, but this does not work well with all sensors.

(!) So, until a better I2C solution is available: use an SPI IMU sensor on ESP32.

NOTE: as of June 2024 this bug is apparently fixed, but not yet confirmed with madflight.

Pinout ESP32

This is the default pinout for ESP32. It is optimized for the Espressiv ESP32 DevKitC (38 pin) board. This pinout is defined in madflight_board_default_ESP32.h, but can be modified with #define HW_PIN_XXX in your program.

FunctionGPIOBoardGPIOFunction
3V3 out3V3Antenna sideGNDGND
reset buttonEN23I2C_SDA
SPI_MISOVP 36 input only22I2C_SCL
IMU_EXTIVN 39 input only1 TXUSB Serial Debug TX
BAT_V34 input only3 RXUSB Serial Debug RX
RCIN_RX35 input only21SPI_MOSI
RCIN_TX32GNDGND
PWM13319SPI_SCLK
PWM22518IMU_CS
PWM326strap 5GPS_TX
PWM42717GPS_RX
PWM51416PWM11
PWM6124PWM10
GNDGNDboot 0PWM9
PWM713strap 2LED
ncD2 9 flashstrap 15PWM8
ncD3 10 flashflash 8 D1nc
ncCMD 11 flashflash 7 D0nc
5V input (*)5VUSB connectorflash 6 CLKnc

Note: During boot the input voltage levels (pull up/pull down) on strap pins have a configuration function, therefor these pins are used as output only.

(*) 5V input via diode from BEC. Without a diode take care not connect USB and the battery at the same time!

Pinout ESP32-S3

This is the default pinout for ESP32-S3. It is optimized for the Espressiv ESP32-S3 DevKitC-1 (44 pin) board. This pinout is defined in madflight_board_default_ESP32-S3.h, but can be modified with #define HW_PIN_XXX in your program.

FunctionGPIOBoardGPIOFunction
3V3 out3V3Antenna sideGGND
3V3 out3V343TX serial debug UART port
reset buttonRST44RX serial debug UART port
PWM141-
PWM252-
PWM3642-
PWM4741-
PWM51540-
PWM61639-
RCIN_TX1738LED
RCIN_RX1837-
I2C_SDA836-
GPS_RX335-
GPS_TX460boot button
I2C_SCL945-
IMU_CS1048RGB_LED
SPI_MOSI1147-
MISO1221-
SCLK1320USB_D+ (serial debug alternate)
IMU_EXTI1419USB_D- (serial debug alternate)
5V in (*)5VGGND
GNDGUSB connectorGGND

(*) 5V input via diode from BEC. Without a diode take care not connect USB and the battery at the same time!

RP2350 / RP2040 Setup and Pinout

madflight works with arduino-pico v4.x.x

Dual Core / FPU / FreeRTOS

RP2350 (Pico2) has dual core, dual FPU, but no FreeRTOS (arduino pico v4.0.1)

RP2040 (Pico) has dual core, no FPU, and FreeRTOS is optional.

madflight uses float and is much happier with RP2350 over RP2040.

madflight on RP2040 uses FreeRTOS and executes the 1000Hz IMU loop on the second core, which is 80% loaded at default 133MHz CPU speed. You can overclock the CPU to get some more headroom.

PWM

Consecutive even/odd PWM pins (e.g. pins 2,3 or 10,11) share the same timer and have the same frequency.

Serial

madflight uses a custom high performance SerialIRQ library.

Pinout Raspberry Pi Pico / Pico2

This is the default pinout for RP2040. It is optimized for the Raspberry Pi Pico (40 pin) board. This pinout is defined in madflight_board_default_RP2040.h, but can be modified with #define HW_PIN_XXX in your program.

FunctionGPIOBoardGPIOFunction
RCIN_TX0USB connectorVBUSnc
RCIN_RX1VSYS5V input via diode (*)
GNDGNDGNDGND
PWM12ENnc
PWM233.3V out3V3
PWM34VREFnc
PWM4528_A2BAT_V
GNDGNDGNDGND
PWM5627_A1-
PWM6726_A0-
GPS_TX8RUNreset button to GND
GPS_RX922IMU_EXTI
GNDGNDGNDGND
PWM71021I2C_SCL
PWM81120I2C_SDA
PWM91219SPI_MOSI
PWM101318SPI_SCLK
GNDGNDGNDGND
PWM111417IMU_CS
PWM1215JTAG pins16SPI_MISO

(*) 5V input via diode from BEC. Without a diode take care not connect USB and the battery at the same time!

Pinout RP2040-Zero

This pinout is optimized for the RP2040-Zero (21 pin) board. This pinout is defined in madflight_board_RP2040-Zero.h, but can be modified with #define HW_PIN_XXX in your program.

FunctionGPIOBoardGPIOFunction
5V input (*)5VUSB connector0RCIN_TX
GNDGND1RCIN_RX
3V3 out3V32PWM1
-293PWM2
BAT_V284PWM3
I2C1_SCL275PWM4
I2C1_SDA266PWM5
IMU_EXTI157PWM6
148GPS_TX
9GPS_RX
10SPI1_SCLK
11SPI1_MISO
12SPI1_MOSI
13IMU_CS

(*) 5V input via diode from BEC. Without a diode take care not connect USB and the battery at the same time!

STM32 Setup and Pinout

madflight works with stm32duino Arduino Core for STM32 v2.x.x

Dual Core / FPU / FreeRTOS

Most supported STM32 targets have a single cores with FPU. FreeRTOS support optional.

madflight runs the IMU loop in interrupt context.

Pinout STM32 Of-the-shelf Flight Controllers

In the src directory you'll find 400+ Betaflight configuration files for commercial flight controllers. Include the madflight_board_betaflight_XXX.h header file of your board, and in your program set '#define HW_USE_XXX' to match your board.

Pinout STM32 Black Pill

This is the default pinout for STM32. It is optimized for the WeAct STM32F411 Black Pill (40 pin) board. This pinout is defined in madflight_board_default_STM32.h, but can be modified with #define HW_PIN_XXX in your program.

FunctionGPIOBoardGPIOFunction
ncVBSWD pins3V33V3 out
LEDC13GGND
-C145V5V input (*)
-C15B9PWM10(t4)
ncRB8PWM9(t4)
-A0B7I2C_SCL
-A1B6I2C_SDA
GPS_TXA2B5PWM8(t3)
GPS_RXA3B4PWM7(t3)
IMU_CSA4B3RCIN_RX
SPI_SCLKA5A15RCIN_TX
SPI_MISOA6A12USB_DP
SPI_MOSIA7A11USB_DN
BAT_IB0A10PWM6(t1)
BAT_VB1A9PWM5(t1)
-B2A8PWM4(t1)
IMU_EXTIB10B15PWM3(t1)
3V3 out3V3B14PWM2(t1)
GNDGB13PWM1(t1)
5V input (*)5VUSB connectorB12-

Internally connected: C13 - LED, A0 - key button

PWM1-6 are connected to timer1, PWM7-8 to timer3 and PWM9-10 to timer4. PWM pins connected to the same timer operate at the same frequency.

(*) 5V input via diode from BEC. Without a diode take care not connect USB and the battery at the same time!

Connecting the IMU Sensor

SPI sensor: (highly recommended over I2C)

  Sensor       Dev Board
SCL/SCLK <---> SPI_SCLK
 SDA/SDI <---> SPI_MOSI
 ADD/SDO <---> SPI_MISO
     NCS <---> IMU_CS
     INT <---> IMU_EXTI
     VCC <---> 3V3
     GND <---> GND

I2C sensor:

  Sensor       Dev Board
     SCL <---> I2C_SCL 
     SDA <---> I2C_SDA
     INT <---> IMU_EXTI
     VCC <---> 3V3
     GND <---> GND

Software Design

  • Keep it simple!!!
  • Forked from dRehmFlight
  • Coded primarily for readability, then for speed and code size.
  • No external dependencies, all modules are included in the src/madflight directory.
  • The madflight flight controller runs standard setup() and loop().
  • It mainly uses plain Arduino functionality: Serial, Wire, and SPI. This makes it possible to have one code base for very different microcontroller platforms.
  • Hardware platform specific libraries are used for PWM and to work around issues in the standard Arduino libraries.
  • madflight can fairly easily ported to other 32 bit microcontrollers that support the Arduino framework. Also porting to other build environments like PlatformIO or CMake should not be a huge effort.
  • The following modules are used:
    • imu Inertial Measurement Unit, retrieves accelerometer, gyroscope, and magnetometer sensor data
    • ahrs Attitude Heading Reference System, estimates roll, yaw, pitch
    • rcin RC INput, retrieves RC receiver data
    • control PID controller and output mixer
    • out Output to motors and servos
    • mag Magnetometer (external)
    • baro Barometer
    • gps GPS receiver
    • bb Black Box data logger
    • cli Command Line Interface for debugging, configuration and calibration
    • cfg Read and save configuration to flash
    • hw Hardware specific code for STM32, RP2040 and ESP32
  • Most modules are interfaced through a global object, for example the imu object has property imu.gx which is the current gyro x-axis rate in degrees per second for the selected IMU chip.
  • For a quick overview of the objects, see header src/madflight/interfaces.h which defines the module interfaces.
  • The module implementations are in subdirectories of the src/madflight directory. Here you find the module header file, e.g. src/madflight/imu/imu.h. In the extras directory your find test programs for the modules, e.g. extras/TestMadflight/imu.ino.
  • The module files are usually header only, that is, the header also includes the implemention.

Changes from dRehmFlight

  • Add support for RP2040, RP2350, ESP32, ESP32-S3, and STM32
  • Dropped Teensy support, but could be re-added by creating a hw_TEENSY.h file. (I just don't have the hardware to test on)
  • Moved all hardware specific code to hw_XXX.h and added hardware specific libraries
  • Reduced the number of global variables
  • Oneshot is implemented as PWM up to 3.9kHz
  • New libs for IMU sensors
  • Changed arming logic
  • Loop rate set to 1kHz to match IMU sensor rate
  • Interrupt driven IMU operation, not setup/loop

Flight Controllers on Github

In (approximate) increasing order of complexity.

Flight ControllerFeaturesDevelopment EnvironmentMicrocontroller
drone-flight-controllerSingle 700 line ino file, no libsArduinoATmega328P
dRehmFlightQuad, Plane, VTOLArduinoArduino Teensy 4
madflightQuad, Plane, VTOL, based on dRehmFlightArduinoESP32, RP2040, and STM32
esp-fcFPV QuadPlatformIOESP32
CrazyflieFPV QuadSTM32F405
esp-droneFPV Quad, based on CrazyflieESP32
BetaflightFPV Quad, based on cleanflightSTM32 F4/F7/H7
EmuFlightMulti-rotor, based on cleanflightSTM32 F4/F7
inavPlane, based on cleanflightSTM32 F4/F7/H7
ArdupilotQuad, Plane, VTOLLinux wafSTM32 F4/F7/H7 or Linux based
PX4-AutopilotQuad, Plane, VTOLSTM32 F4/F7/H7

Disclaimer

This code is a shared, open source flight controller for small micro aerial vehicles and is intended to be modified to suit your needs. It is NOT intended to be used on manned vehicles. I do not claim any responsibility for any damage or injury that may be inflicted as a result of the use of this code. Use and modify at your own risk. More specifically put:

THIS SOFTWARE IS PROVIDED BY THE CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Logo image copyright (c) 1975 Deutsches MAD Magazine. This project is not associated with MAD Magazine.