This is a short guide for setting up ArduPilot on a flying wing. I use an Omnibus F4 that was previously set up for INAV (so motor on 1, elevons on 3/4), so most of this guide will be geared to that. If you use a different controller, your mileage may vary.
You should keep the full list of ArduPilot parameters open, for your reference while tuning.
Because building ArduPilot is a bit complicated, I've written a short script that uses Docker to build AP in a controlled environment.
Copy it from here, save it to a file called docker_build.sh
in the root of the ArduPilot repo, and run it with docker_build.sh <your board>
. Output files will be stored in build/<yourboard>/bin/
, and you can flash them with the INAV configurator by putting your board in DFU mode and uploading the arduplane_with_bl.hex
file:
#!/usr/bin/env bash
set -euo pipefail
if [ $# -ne 1 ]
then
echo "No board supplied, run as ./docker_build.sh <board name> or ./docker_build.sh list"
exit 1
fi
BOARD=$1
cd "$(git rev-parse --show-toplevel)"
git submodule update --init --recursive
git checkout Dockerfile
echo "RUN pip install intelhex" >> Dockerfile
echo 'ENV PATH="/home/ardupilot/.local/bin:/usr/lib/ccache:/ardupilot/Tools/autotest:/opt/gcc-arm-none-eabi-6-2017-q2-update/bin:${PATH}"' >> Dockerfile
docker build . -t ardupilot
git checkout Dockerfile
docker run --rm -it -v "$(pwd)":/ardupilot ardupilot:latest ./waf configure --board="$BOARD"
docker run --rm -it -v "$(pwd)":/ardupilot ardupilot:latest ./waf build
The values in this section are specific to the Omnibus F4, but the settings aren't, so you'll usually need to adjust your outputs to your specific configuration but you probably won't need to skip many of the steps here.
BRD_ALT_CONFIG=1
, to get UART 3 to act like a UART instead of I2C on the Omnibus F4.AHRS_ORIENTATION
.
SERIAL2_PROTOCOL = 23 (RCIN)
SERIAL2_BAUD=115
SERIAL2_OPTION=4
RSSI_TYPE=3
RC2_REVERSED=1
.
SERVO1_FUNCTION=70
SERVO1_MIN=1000
SERVO1_MAX=2000
SERVO1_TRIM=1000
SERVO3_FUNCTION=77
SERVO3_MIN=1000
SERVO3_MAX=2000
SERVO3_TRIM=1500
SERVO4_FUNCTION=78
SERVO4_MIN=1000
SERVO4_MAX=2000
SERVO4_TRIM=1500
All these values are necessary, because usually the SERVOn_TRIM
won't be at 1500.SERVO_BLH_OTYPE=4
for DShot150 and SERVO_BLH_MASK=1
to enable it for the motor.COMPASS_ENABLE=0
if you don't have a compass, otherwise calibrate it (not detailed here).TERRAIN_ENABLE=0
to get rid of the terrain warning.AHRS_TRIM_Y
and check that FBWA mode flies level.LOG_BACKEND_TYPE=0
.OSD_ARM_SCR
/OSD_DSARM_SCR
.SERVO_AUTO_TRIM=1
so the aircraft trims itself while flying.FS_SHORT_ACTN
/FS_SHORT_TIMEOUT
/FS_LONG_ACTN
/FS_LONG_TIMEOUT
. I tend to disable the short action and set long to RTL.RTL_CLIMB_MIN=30
so the aircraft climbs first before starting to return to home.ACRO_LOCKING=1
to avoid drifting when you aren't moving the sticks.AUTOTUNE_LEVEL
according to how aggressive you want the tune.ACRO_PITCH_RATE
/ACRO_ROLL_RATE
according to your craft.THR_PASS_STAB=1
so you have total throttle control in ACRO/FBWA/STABILIZE.ARSPD_FBW_MIN
/ARSPD_FBW_MAX
to the minimum and maximum airspeed you want auto modes to fly (see the TECS tuning guide below for details).MIN_GNDSPD_CM
so the craft makes an effort to return even under high winds. WARNING: Might make throttle pulse or have other unwanted side-effects.TKOFF_THR_MAX
to the desired max takeoff throttle.TKOFF_ALT
to the altitude you want takeoff to reach.THR_SUPP_MAN=1
so you can manually set the autolaunch "idle" throttle (before the throw).TKOFF_THR_MINACC=18
for the takeoff throw to activate takeoff with a minimum of 2g.TKOFF_LVL_PITCH
to your desired angle (20 is a good value).TKOFF_THR_DELAY
to the number of deciseconds that you want the motor to wait before it starts up.TKOFF_THR_SLEW=127
to make the throttle spin up to full faster (within 0.8 sec).old_value+pitch*Ï€/180
to get the new value (in radians).To tune the TECS, a helpful resource is the TECS tuning guide. Make sure you have run an autotune beforehand, and continue with the tuning below.
In tuning, there are two stages:
You should perform the measurements in four stages, all in the FBWA mode:
Fly straight and note down:
Set the throttle to the maximum throttle percentage from the previous step and start slowly pulling back on pitch until your airspeed equals your "comfortable cruise speed" from the previous step. Note down:
Set the throttle to 0 and start pushing on the pitch stick until your airspeed equals your "comfortable cruise speed" from the previous step. Note down:
Keep the throttle at 0 and pitch down until you reach your desired maximum speed from step 1. Note down:
You're done with this step.
After you have the above measurements, you're ready to tune things.
For the level flight measurements:
TRIM_ARSPD_CM
to your "comfortable cruise speed".TRIM_THROTTLE
to your cruise throttle percentage.ARSPD_FBW_MAX
to something a bit less than the maximum airspeed you achieved in level flight.THR_MAX
to the throttle percentage at max speed.ARSPD_FBW_MIN
to the slowest speed you could turn at without stalling (maybe go a bit higher for some margin).STAB_PITCH_DOWN
to the pitch angle that keeps you from stalling.For the ascent measurements:
TECS_PITCH_MAX
to the pitch angle you measured.TECS_CLMB_MAX
to the climb rate you measured.For the descent measurements:
TECS_SINK_MIN
to the descent rate you measured.For the max descent measurements:
TECS_PITCH_MIN
to the pitch angle you measured.TECS_SINK_MAX
to the descent rate you measured.Afterwards:
LIM_PITCH_MAX
to something higher than TECS_PITCH_MAX
.
This is the maximum pitch you'll be achieving in FBWA.LIM_PITCH_MIN
to something lower than TECS_PITCH_MIN
.
This is the minimum pitch you'll be achieving in FBWA.That's it!
(Many thanks to Michel Pastor for his help with everything in this note.)
Last updated on April 10, 2021. For any questions/feedback, email me at hi@stavros.io.