MethodicConfigurator

How to methodically tune any ArduCopter

Cinewhoop Diatone Taycan MX-C

For illustrative purposes, we will use the small 3’’ multicopter depicted above, but the tuning sequence we developed at IAV GmbH will work on almost any other multicopter. Parts of Section 1 and Sections 2 to 6 apply to all ArduPilot vehicles: ArduPlane, ArduRover, ArduBoat, ArduSub, ArduBlimp …

This method uses the latest available ArduPilot WebTools, some of the new features of ArduCopter 4.3 and above and best practices from the ArduPilot Community.

We will detail the firmware parameters to change, the sequence of how to change them, help you to find the value for each parameter, explain which test flights to conduct and the order in which to conduct them and help you document all your steps for traceability. This applies industry-proven software configuration management (SCM) techniques to tuning an ArduCopter vehicle. You will be able to tune multiple vehicles (think production line) using this method and still have individual traceability of each parameter change on each vehicle.

  1. Select the vehicle components
  2. Install required Software
  3. Input vehicle components and component connections into ArduPilot Methodic Configurator
  4. Perform IMU temperature calibration before assembling the autopilot into the vehicle (optional)
  5. Assemble all components except the propellers
  6. Basic mandatory configuration
  7. Assemble propellers and perform the first flight
  8. Minimalistic mandatory tuning
  9. Standard tuning (optional)
  10. Improve altitude under windy conditions (optional)
  11. System identification for analytical PID optimization (optional)
  12. Position controller tuning (optional)
  13. Productive configuration
  14. Conclusion

1. Select the vehicle components

While choosing an Autopilot and other hardware components avoid these components

Use tools like ecalc for multirotor to find a suitable set of components to meet your needs.

eCalc example screenshot

1.1 Multicopter hardware best-practices

  1. Robust frame construction: A stable and rigid frame is crucial for stable and safe flight behavior. Carbon frames are recommended but not essential, and remember carbon is an electrical conductor.
  2. ESC telemetry: Use only ESCs that provide at least RPM telemetry. It simplifies Notch filter tuning and improves its response-time and accuracy.
  3. Vibration reduction: Vibrations reduce the efficiency, stability and lifespan of the drone. Propellers and motors are the source of most of the vibrations. All components must be securely fastened to minimize vibrations and avoid damage caused by vibrations. Stiff frames reduce vibrations.
    • X and Y vibrations are caused by prop and/or motor imbalance - all propellers must be carefully balanced.
    • Z vibrations are caused by the downwash of each blade hitting the arm and the forward traveling propeller hitting the oncoming air when moving.
  4. Protection of sensors from external disturbances:
    1. Vibration-damping mounting of the FC
    2. Separation of compass and high-current paths: To reduce electromagnetic interference, it is recommended to spatially separate the compass (likely integrated with GNSS receivers) from high-current paths and magnetic sources such as motors and power distribution systems/cables. Keep positive and negative wires close together using a gentile twist, brade or regularly spaced zip ties.
    3. Protection of barometer from airflow: The barometer must be protected from wind and airflow or turbulence generated by the propellers. A small piece of open-cell foam placed over the sensor acts as a low-pass filter, ensuring accurate altitude measurements.
    4. GNSS systems are likely to be affected by USB3 devices. Keep possible negative influences in mind while using USB3 components.
  5. Proper cable management: Cables and wires must be organized sensibly to prevent entanglement or damage during flight. It must be ensured that no cables hinder movable parts such as propellers or gimbal mechanisms, or are damaged by them. Flexible, silicone-coated cables for data transfer save weight and reduce vibration transmission. Weak connectors are prone to loosening under the influence of vibration.
  6. Weight distribution: An even weight distribution of the drone with the FC at the center of gravity improves stability and flight control. Components such as batteries, sensors, cameras, and other payloads must be positioned evenly to achieve uniform weight distribution and maximum fit between the geometric and physical center of gravity.
  7. Battery placement: The battery is often located in the center of the frame to ensure stability during flight. It must be ensured that the battery is rigidly mounted and secured to prevent slipping or unintentional disconnection during operation. Additionally, when properly attached, the battery acts as an inertial mass and helps damp vibrations. Beware of landing directly on the battery since most of the batteries do have a resistant shell.
  8. Voltage monitoring: to dynamically scale the PIDs and maintain stable flight in low battery conditions.
  9. Current monitoring: to compensate for the dynamic magnetic field caused by the high motor currents.
  10. FC Power supply: Must provide enough current for the flight controller, GNSS receivers and other payloads operating on 5V.
  11. Roll/Pitch/Yaw-Imbalance: When mounting the motors on the arms, especially on round arms, make sure that all motors and propellers are perfectly level so that the thrust produced is directed straight down. Misaligned motors will cause the multicopter to drift. Depending on which motors are misaligned and their direction of misalignment, the multicopter drifts laterally forward, backward, left, right, or axially around the Z-axis, and efficiency is reduced accordingly.
  12. Helical GNSS antennas: These kinds of antennas are the preferred choice for drones and their benefits justify the extra cost.
  13. STM32 H7 processor family: Flight controllers that use these processors, have enough processing power and memory to run ArduCopter firmware without restrictions.

1.2 Our (example) vehicle

To demonstrate how to methodically tune a ArduCopter vehicle we selected a small copter that we could fly and tune indoors. It uses the following components:

Type Part
Frame Diatone Taycan MX-C
Flight Controller Matek H743 SLIM V3
ESC Mamba System F45_128k 4in1 ESC
Motors 4x T-Motor 15507 3800kv
Propeller 4x CineWhoop 3", 8-Blade
BEC with voltage/current monitor Holybro PM02 V3
Battery SLS X-Cube 4S 1800mAh 40C/80C
GNSS Receiver Holybro H-RTK F9P Helical
SDCard Any FAT32 or exFAT formated fast Micro-SDCard > 8 GiB
RC Receiver TBS Crossfire Nano RX se
RC Transmitter Radiomaster TX16S with EdgeTx and Yaapu scripts
Remote ID transmitter Holybro Remote ID transmitter

Your vehicle will be different as your application will have different requirements.

2. Install required Software

To configure and operate your vehicle you need at least these software:

Use Mission Planner to flash the latest stable ArduCopter, ArduPlane, ArduRover, ArduSub or ArduBlimp firmware for your flight controller.

2.1 Used software summary

The table bellow summarizes the software used in this guide. Download and install them as you progress in the guide.

Software Version Description
Mission Planner latest beta Ground control station (PC software) used for configuring and operating the vehicle
ArduPilot Methodic Configurator latest A clear ArduPilot configuration sequence
ArduCopter 4.4.4 or 4.5.5 Flight controller firmware
BLHeliSuite32 32.9.06 PC software to flash and configure ESCs with BLHeli_32 ARM firmware
BLHeli_32 ARM 32.8 ESC firmware with Bidir Dshot support
EdgeTx companion 2.9.2 PC software for configuring and updating EdgeTX based RC transmitters
EdgeTx 2.9.2 Radiomaster TX16S firmware with touch screen support
Yaapu scripts 2023-11-08 Display vehicle telemetry on the Radiomaster TX16S
Simple text editor: Notepad++, nano or code any Allows editing plain text files without undesired text changes. Do not use microsoft word!
MAVExplorer latest Analyze dataflash (.bin) log files
Scripted MagFit flightpath generation latest Lua script to generate a MagFit flight path
ecalc for multirotor online Finds a suitable set of components that meet your needs
ArduPilot Hardware Report online Provides an overview of connected hardware from a .bin log and visualization of sensor position offsets.
ArduPilot Filter Review Tool online Aid in configuring and validating the Harmonic Notch filters
ArduPilot Filter Analysis online Bode plot tool to give insight into gyro low-pass and notch filter attenuation and phase lag
ArduPilot PID Review Tool online Review PID tune in the frequency domain. Step response estimate is generated.
ArduPilot MAGFit in flight compass calibration online Do compass calibration using a flight log
Ardupilot Log Viewer online Log viewer, analyzer and plotter. Can also do MagFit
Add grid to image online Add a grid overlay to any image
SketchAndCalc online Calculate areas

3. Input vehicle components and component connections into ArduPilot Methodic Configurator

The ArduPilot Methodic Configurator needs to know which components you used/plan to use and how you connected/plan to connect them to the flight controller (autopilot). It uses this information to automatically pre-select configuration settings relevant to your specific vehicle.

So, start the ArduPilot Methodic Configurator and input select a vehicle that resembles yours and input vehicle components and component connections information into the ArduPilot Methodic Configurator component editor window:

  1. Close Mission Planner, if it is open on the PC.
  2. Connect the flight controller to the PC via a USB cable and wait 7 seconds.
  3. Open ArduPilot Methodic Configurator, and connect it to the vehicle. FC connection and parameter download
  4. Now using New subsection New vehicle
  5. Fom the existing templates, select the one most similar to your vehicle: New vehicle
  6. select the destination directory, give it a name and press Create vehicle configuration directory from template
  7. On the component editor window, add all the details of the components of your system as we did in Section 1.2: Component editor window
  8. Make sure to scroll all the way down and enter all the information requested, even if it does not seam important to you.
  9. Click the Save data and start configuration button on the bottom
  10. You now have a vehicle configuration directory with the name that you selected. But the files are just templates, you need to edit them in the next steps.

4. Perform IMU temperature calibration before assembling the autopilot into the vehicle (optional)

IMU temperature calibration reduces the probability of Accel inconsistent and Gyro inconsistent errors and reduces the time required to arm the vehicle. IMU temperature calibration requires lowering the temperature of the autopilot (flight controller) to circa -20°C. That is harder to do once the autopilot is assembled inside the vehicle, hence it is done now.

4.1 Setup IMU temperature calibration

  1. Start the software
  2. On ArduPilot Methodic Configurator select 02_imu_temperature_calibration_setup.param on the Current intermediate parameter file: Combobox if not already selected.
  3. Read the Forum Blog: and Wiki: documentation by pressing on the blue URL links.
  4. Edit the 02_imu_temperature_calibration_setup.param parameters’ New Value and Change Reason using the ArduPilot Methodic Configurator parameter editor and press Upload selected params to FC, and advance to next file.
  5. When ArduPilot Methodic Configurator asks you Do you want to provide a .bin log file and run the IMU temperature calibration using it? select No and close the program.
  6. Power off the flight controller and remove the battery.
  7. Place the flight controller without battery in a freezer capable of reaching your vehicle’s minimum expected operation temperature (-18°C in our case).
  8. Once the flight controller is completely cooled down to its minimum expected operation temperature, take it out and power it. Do not move the flight controller for one or two hours.
  9. If you have a buzzer connected, you will hear a short periodic beep while the calibration is in progress. When the calibration is complete, a completion tune will play. If you have notification LEDs on your flight controller they will cyclically flash red, blue and green while calibrating. If you do not have a buzzer connected nor notification LEDs, monitor the INS_TCALn_ENABLE parameters. On completion, the INS_TCALn_ENABLE parameters will change to 1 (enable) for each calibrated IMU.
  10. Power it off, and remove the micro SDCard
  11. Copy the latest .bin log file in the micro SDcard from /APM/LOGS to your PC
  12. Insert the micro SDcard back into the flight controller

4.2 Calculate IMU temperature calibration

  1. Connect a USB cable to the FC and open ArduPilot Methodic Configurator. It will ask you again Do you want to provide a .bin log file and run the IMU temperature calibration using it? Select Yes and point it to the .bin file that you just downloaded.
  2. Wait until finished It can take 10 Minutes or more look at the produced graphs they are also automatically saved to disk on the vehicle directory
  3. Press Upload selected params to FC, and advance to next file.

The graphic below depicts the accelerometer drift versus time and the board temperature versus time. The temperature curve, depicted in black, is logarithmic as expected. The other curves are smooth, proving that the flight controller was not moved in the process and the calibration is valid. As can be seen, before the calibration temperature changes caused a big change in accelerometer/gyro drift. After the calibration, temperature changes will cause no significant accelerometer/gyro drift changes.

MatekH743Slim IMU temperature calibration

5. Assemble all components except the propellers

Now that the optional IMU temperature calibration is done we must assemble and connect all components except the propellers.

Read the Multicopter hardware best-practices section again before assembling the vehicle.

If you changed the way the components are connected to the flight controller (FC), re-enter the updated information into ArduPilot Methodic Configurator component editor window.

Always connect the vehicle battery before connecting the USB cable (if you are using one) between the PC and the flight controller. Always disconnect the USB cable (if you are using one) between the PC and the flight controller before disconnecting the vehicle battery.

5.1 Assembly of the example vehicle

We connected the components as depicted below. The figure excludes the LiPo battery and the PM02 BEC with a voltage/current monitor.

Component Flight controller connections
T-Motor F45 4in1 ESC V2 G, G, Vbat, not Connected, S4, S3, S2, S1, Cur, Rx8 (SERIAL5)
Holybro PM02 V3 not connected, G, Vbat2, Curr2, not Connected, not Connected
Holybro H-RTK F9P Helical 5V, Tx2, Rx2, CL1, DA1, not connected, not connected, 3V3, Buzz, G
TBS Crossfire Nano RX se G, 5V, Rx6, Tx6

Matek H743, Holobro F9p, T-Motor F45 4in1 ESC and TBS Crossfire Nano rx se connections

6. Basic mandatory configuration

6.1 Configure flight controller orientation

Follow mounting the autopilot documentation to determine the correct value of the AHRS_ORIENTATION parameter.

6.1.1 Use ArduPilot Methodic Configurator to edit the parameter file and upload it to the flight controller

  1. The parameter file for this particular step is 04_board_orientation.param other steps will use other parameter files parameter file editor window
  2. On ArduPilot Methodic Configurator select 04_board_orientation.param on the Current intermediate parameter file: Combobox.
  3. Read the documentation links inside the 04_board_orientation.param documentation
  4. Add or Delete parameters if necessary, using the respective GUI buttons
  5. Edit the parameters’ New Value and Change Reason to suit your requirements. The Change Reason field is extremely important because:
    • if forces you to think, causing rational decisions instead of impulsive ones
    • justifies your decisions on a vehicle certification process required in most countries
    • allows for someone else to see if you know what you are doing
    • allows for someone else (or yourself after a few weeks) to understand your rationale
  6. Press Upload selected params to FC, and advance to next file button.

6.2 Configure the RC receiver

In our setup, we use EdgeTX firmware on the RC transmitter.

Download and install EdgeTX Companion to your PC. Start it and configure it as depicted below.

EdgeTX companion setup

After that, use a micro SDcard to update the firmware on the Radiomaster TX16S and copy the yaapu scripts to the /WIDGETS/yaapu directory on the micro SDcard.

Once the RC transmitter is running EdgeTx you can load the Taycan MX-C EdgeTX configuration file into EdgeTX companion and upload it to the radio. Or simply copy only the settings that you require, EdgeTX companion is very flexible.

In our setup, we used an advanced RC receiver that cannot be fully configured using Mission Planner’s SETUP >> Mandatory Hardware >> Radio Calibration menu.

Repeat the steps from Section 6.1.1 to edit and upload the 05_remote_controller.param file

After that test the RC failsafe

6.3 Configure telemetry

The RC transmitter we used has a big color display where telemetry data is displayed, nevertheless, we use telemetry data for real-time flight monitoring with Mission Planner or QGroundControl.

Repeat the steps from Section 6.1.1 to edit and upload the 06_telemetry.param file

Once this is operating we no longer need the USB connection to the vehicle. We can now use the telemetry connection instead.

6.4 Configure the ESC

In our setup, we used a Bi-directional Dshot ESC that cannot be fully configured using Mission Planner’s SETUP >> Mandatory Hardware >> Servo Output menu.

Repeat the steps from Section 6.1.1 to edit and upload the 07_esc.param file

The step above configured ESC communication pass-thru. In our vehicle, we use BLHeli_32 ARM ESC firmware. So we use BLHeliSuite32 Version 32.9.0.6 to configure the ESCs. Flash the Firmware version described in the table above. Configure the parameters to match the figures below.

Tuning your BLHeli_32 to stop desyncs and improve motor performance in your FPV quadcopter

ESC Setup

ESC Overview

6.5 Configure the primary battery monitor

In our setup, the battery voltage is measured directly at the flight controller Vbat pin and the current is measured at the 4-in1 ESC Curr pin.

Repeat the steps from Section 6.1.1 to edit and upload the 08_batt1.param file

6.6 Configure the redundant (secondary) battery monitor (optional)

To be on the safe side we used a Holybro PM02 as a redundant secondary voltage and current monitor. One other option would be the CBU 2-8s DroneCAN Battery Monitor and Current Sensor.

Repeat the steps from Section 6.1.1 to edit and upload the 09_batt2.param file

6.7 Configure the GNSS receiver(s)

GNSS receivers very often contain a magnetometer (compass) sensor. So they need to be configured before proceeding to the next step.

Repeat the steps from Section 6.1.1 to edit and upload the 10_gnss.param file

6.8 Initial attitude PID gains (vehicle size dependent)

Propeller size has a big influence on the vehicle dynamics, this adapts controller response to it.

Repeat the steps from Section 6.1.1 to edit and upload the 11_initial_atc.param file

When asked Should the FC values now be copied to the 12_mp_setup_mandatory_hardware.param file? select No and close the ArduPilot Methodic Configurator software.

6.9 Configure “Mandatory Hardware” Parameters

Open Mission Planner, connect to the flight controller and select SETUP >> Mandatory Hardware and work yourself through all the submenus as described below. DO NOT SKIP ANY STEP.

Frame Type

This relates to the FRAME_CLASS and FRAME_TYPE parameters.

Initial Tune Parameters

Answer the questions that Mission Planner asks, select Add suggested settings for 4.0 and up (Battery failsafe and Fence) and upload the calculated parameters to the flight controller by pressing Upload to FC.

MP Initial Tune Parameters questions

MP Initial Tune Parameters results

Accel Calibration

Follow the ArduPilot wiki instructions and calibrate the accelerometers. For small vehicles use:

For very large vehicles:

Compass

Follow the ArduPilot wiki instructions and calibrate the compass(es). Disable internal compasses if the battery or power wires are close to the flight controller. Do not select Automatically learn offsets it makes little sense on a multicopter. And we will do in-flight MagFit later

If you have a large vehicle you might want to use large vehicle MagCal instead.

Radio Calibration

Follow the ArduPilot wiki instructions and calibrate the Remote Control. Turn on your RC Transmitter and move the sticks around. Make sure all transmitter channels move across their entire range.

Servo Output

Change the parameters according to your requirements.

ESC Calibration

Do not make changes here, these parameters will be set later on the Motor/Propeller order and direction test section

Flight Modes

Define the flight modes you plan to use. Do not use POSHOLD, use LOITER instead. Both only work outdoors because they require a good GNSS signal quality with low variance. If that is not possible, GPS glitches will occur and ALTHOLD flight mode is recommended instead.

Failsafe

These are very important and can save your vehicle in case of failure. Configure at least Radio Failsafe, Battery Failsafe and Geofence

HW ID

This is just informational. No need to change anything.

ADSB

Change the parameters according to your requirements.

Last step

The changes you did in the steps above have been stored in your vehicle. Most of the changed parameters are vehicle-instance specific and can not be reused between two vehicles, no matter how similar they are. Close Mission Planner.

6.10 General configuration

Now do some general configuration

  1. Connect the flight controller to the PC
  2. Start ArduPilot Methodic Configurator and select the vehicle directory where you previously stored your intermediate parameter files.
  3. When ArduPilot Methodic Configurator asks you Should the FC values now be copied to the 12_mp_setup_mandatory_hardware.param file? select Yes
  4. Select 13_general_configuration.param on the Current intermediate parameter file: Combobox.
  5. Read the documentation links inside the 13_general_configuration.param documentation
  6. Edit the parameters’ New Value and Change Reason to suit your requirements
  7. Press Upload selected params to FC, and advance to next file button.

6.11 ArduPilot Hardware Report

For this test, you need to:

  1. Visit the ArduPilot Hardware report on your PC and upload the .bin file you got in the previous section.
  2. Take a look at the results

It should look like the following picture. If it doesn’t, go back and perform the missing calibration(s).

Hardware-Report after IMU temperature compensation

6.12 Configure Logging

MP LOG_BITMASK parameter

Repeat the steps from Section 6.1.1 to edit and upload the 13_Logging.param file

The table below explains which bit is responsible for which .bin dataflash log message(s):

Log message vs. LOG_BITMASK value
MessagedescriptionLog rateLOG_BITMASK
field namebitvalue
SIDDSystem ID dataSCHED_LOOP_RATE / 1ATTITUDE_FAST and ATTITUDE_MED1 and 03
SCHED_LOOP_RATE / 2ATTITUDE_FAST02
SCHED_LOOP_RATE / 4ATTITUDE_MED01
SCHED_LOOP_RATE / 8--0
SIDSSystem ID settingsSCHED_LOOP_RATE / 1ATTITUDE_FAST and ATTITUDE_MED1 and 03
SCHED_LOOP_RATE / 2ATTITUDE_FAST02
SCHED_LOOP_RATE / 4ATTITUDE_MED01
SCHED_LOOP_RATE / 8--0
RATEDesired and achieved vehicle attitude ratesSCHED_LOOP_RATE / 1ATTITUDE_FAST and ATTITUDE_MED1 and 03
SCHED_LOOP_RATE / 2ATTITUDE_FAST02
SCHED_LOOP_RATE / 4ATTITUDE_MED01
SCHED_LOOP_RATE / 8--0
ATSCScale factors for attitude controllerSCHED_LOOP_RATE / 1ATTITUDE_FAST and ATTITUDE_MED1 and 03
SCHED_LOOP_RATE / 2ATTITUDE_FAST02
SCHED_LOOP_RATE / 4ATTITUDE_MED01
SCHED_LOOP_RATE / 8--0
ATTCanonical vehicle attitudeSCHED_LOOP_RATEATTITUDE_FAST01
10 HzATTITUDE_MED12
IMUInertial Measurement Unit dataSCHED_LOOP_RATEIMU_FAST and ATTITUDE_FAST18 and 0262145
25 HzIMU7128
GPSInformation received from GNSS systems attached to the autopilot~ 5 HzGPS24
GPAGPS accuracy information
UBX1uBlox-specific GPS information (part 1)
UBX2uBlox-specific GPS information (part 2)
GRAWRaw uBlox datas
GRXHRaw uBlox data - header
GRXSRaw uBlox data - space-vehicle data
TERRTerrain database information
PMautopilot system performance and general data dumping ground1 HzPM38
XKF0EKF3 beacon sensor diagnostics25Hz if ATTITUDE_FAST is set, else 10Hz---
XKF1EKF3 estimator outputs
XKF2EKF3 estimator secondary outputs
XKF3EKF3 innovations
XKF4EKF3 variances
XKF5EKF3 Sensor innovations (primary core) and general dumping ground
XKFSEKF3 sensor selection
XKQEKF3 quaternion defining the rotation from NED to XYZ (autopilot) axes
XKV1EKF3 State variances (primary core)
XKV2more EKF3 State Variances (primary core)
XKTEKF3 timing information
AHR2Backup AHRS data
POSCanonical vehicle position
CTRLAttitude Control oscillation monitor diagnostics10HzCTUN416
RFNDRangefinder sensor information
PRXProximity Filtered sensor data
PRXRProximity Raw sensor data
BCNBeacon information
CTUNControl Tuning information100Hz
PSCNPosition Control North10HzNTUN532
PSCDPosition Control Down
PSCEPosition Control East
RCINRC input channels to vehicle10HzRCIN664
RCI2(More) RC input channels to vehicle
RSSIReceived Signal Strength Indicator for RC receiver
VIBEProcessed (acceleration) vibration information10HzIMU or IMU_FAST or IMU_RAW19 or 18 or 7-
CMDExecuted mission command informationon eventCMD8256
MAVCMAVLink command we have just executed
BATGathered battery data??CURRENT9512
BCLBattery cell voltage information
MCUMCU voltage and temperature monitoring
POWRSystem power information
RCOUServo channel output values 1 to 1410HzRCOUT101024
RCO2Servo channel output values 15 to 18
RCO3Servo channel output values 19 to 32
OFOptical flow sensor data??OPTFLOW112048
PIDNProportional/Integral/Derivative gain values for NorthSCHED_LOOP_RATE if ATTITUDE_FAST is set else 10HzNTUN and PID12 and 54128
PIDEProportional/Integral/Derivative gain values for East
PIDRProportional/Integral/Derivative gain values for RollSCHED_LOOP_RATE if ATTITUDE_FAST is set else 10HzPID124096
PIDPProportional/Integral/Derivative gain values for Pitch
PIDYProportional/Integral/Derivative gain values for Yaw
PIDAProportional/Integral/Derivative gain values for Altitude
MAGInformation received from compasses??COMPASS138192
CAMCamera shutter informationon eventCAMERA1532768
TRIGCamera shutter information
MOTBMotor mixer information10HzMOTBAT17131072
ACCIMU accelerometer dataSCHED_LOOP_RATEIMU_RAW19524288
GYRIMU gyroscope data
VSTBMotor mixer informationSCHED_LOOP_RATEVIDEO_STABILISATION201048576
FTNFilter Tuning Message - per motorSCHED_LOOP_RATEFTN_FAST212097152
FTNSFilter Tuning Message
FTN1FFT Filter Tuning25 Hz
WINCWinch10HzAnyanyany

6.13 Motor/Propeller order and direction test

Start by checking the motor numbering with the Mission Planner Motor test without propellers. Remember the correct order is A, B, C, D and not 1, 2, 3, 4.

Make sure the MOT_SPIN_ARM is high enough so that all motors spin reliably. Make sure the MOT_SPIN_MIN is at least 0.03 higher than MOT_SPIN_ARM.

!!! If you get this test wrong or skip it, you might destroy your vehicle and endanger yourself !!!

Do not try to test the attitude controller without propellers, it will not work, such tests are inconclusive and meaningless. Do not try to test the attitude controller with the vehicle tied down on the ground, it will not work, such tests are inconclusive and meaningless. At this point, the vehicle does not react to roll, pitch, yaw or thrust inputs.

Now mount the propellers on the vehicle.

After that, follow the setting Motor Range to adjust the motor demand by the flight controller to the limitations of the ESC.

Motor Thrust scaling (MOT_THST_EXPO, MOT_SPIN_MIN and MOT_SPIN_MAX)

These three parameters linearize (correct) the non-linear thrust vs. PWM response of the propulsion system (battery, ESC, motors, propellers). They are crucial for the stability of the vehicle. If this is set too high we see an increase in gain at the lower end of the thrust range and a decrease in gain at the upper end.

Therefore when set too high you can see instability at low throttle and if set too low you can see instability at high throttle.

The automation on SETUP >> Mandatory Hardware >> Initial Tune Parameters gave you a good starting point on their values. But we recommend using a Trust Stand or Olliw method or ArduPilot DIY Thrust Stand to determine their value.

At the time of writing Automatic MOT_THST_EXPO estimation lua script is not yet ready for production use.

We used an oversized test stand to test the motors. Since the test stand was too big for a single motor we tested all four motors at once. This was our setup:

![motor_test_stand_with_drone_cropped 316x499](/MethodicConfigurator/images/blog/motor_test_stand_with_drone_cropped.jpg)

We fixed and updated Cell G8 as well as the plot’s Data range of the original ArduPilot Wiki Spreadsheet creating this corrected version

We imported the data into the spreadsheet and created this graph:

![motor_thrust_chart 690x389](/MethodicConfigurator/images/blog/motor_thrust_chart.PNG)

Repeat the steps from Section 6.1.1 to edit and upload the 15_motor.param file

6.14 Optional PID adjustment

If you have a very small, or a very large vehicle that requires non-default PID values for a safe flight. Usually, smaller vehicles require lower than default PID rate values. Larger vehicles usually require higher than default PID rate values.

Repeat the steps from Section 6.1.1 to edit and upload the 16_pid_adjustment.param file

6.15 Remote ID (aka Drone ID)

Read and follow ArduPilot’s Remote ID setup instructions. You might have to build OpenDroneID firmware for production.

Repeat the steps from Section 6.1.1 to edit and upload the 17_remote_id.param file

6.16 Notch filters setup

Configure the gyro noise reduction notch filters with an estimation of the operation parameters. The estimation will be improved after the first flight.

Repeat the steps from Section 6.1.1 to edit and upload the 18_notch_filter_setup.param file

When asked Should the FC values now be copied to the 19_notch_filter_results.param file? select No and close the ArduPilot Methodic Configurator software.

7. Assemble propellers and perform the first flight

Assemble the propellors in the vehicle ensuring that they are balanced in order to reduce vibrations. High vibrations will cause your vehicle to behave eradicaly endangering people and property.

Now that all mandatory configuration steps are done and the props are on you can perform the first flight.

7.1 First flight: Motor Thrust Hover and Harmonic Notch data collection

For more detailed information visit the First flight

Test the initial setup on the ground in stabilize flight mode by using as little RC transmitter throttle as possible without taking off. At this sweet spot, inspect all axes (roll, pitch and yaw) by providing small RC transmitter stick inputs. If the multicopter behaves correspondingly, the setup is good to go.

After some careful test maneuvers switch to ALTHOLD and hover for 30 to 40 seconds one to two meters above the ground. Land and disarm.

Immediately check for hot motors. If the motors are too hot, check the .bin dataflash log, high or oscillating RATE.*out values indicate which PID gain you should reduce to remove the output oscillations causing the motors to heat up.

8. Minimalistic mandatory tuning

These are the very minimum tuning steps required for a stable flight:

8.1 Notch filter calibration

Load the .bin log from the first flight onto the online Ardupilot Filter Review tool Follow the instructions from Peter Hall on his Blog Post to configure the Harmonic Notch filter(s). The graph below is a bode diagram of the gyro signals before and after the low-pass and Harmonic Notch filters. As you can see, the filters remove most of the vibration noise from the gyro sensors.

Filter IMU1

Below is the configuration we used.

Filter Configuration

  1. On ArduPilot Methodic Configurator select 19_notch_filter_results.param on the Current intermediate parameter file: Combobox.
  2. When asked Should the FC values now be copied to the 19_notch_filter_results.param file? select No.
  3. Read the documentation links inside the 19_notch_filter_results.param documentation
  4. Edit the parameters’ New Value and Change Reason to suit your requirements
  5. Press Upload selected params to FC, and advance to next file button.

Load the .bin log from the first flight onto the online Ardupilot Log Viewer or into Mission Planner. Take a look at the VIBE.VibeX, VIBE.VibeY, VIBE.VibeZ graphs they all should be below 15

According to common ArduPilot forum knowledge, and quoting @xfacta:

Now upload the .bin log to the Hardware-Report Tool once again to check CPU load and loop times, which in our case look like this:

Hardware-Report CPU load

Hardware-Report CPU loop times

8.2 Configure the throttle controller

Use the .bin log from the first flight to set the parameters described on the 20_throttle_controller.param file.

8.3 Configure the EKF altitude source weights

In some situations you will need to configure the expected noise levels of the altitude sources. And the weight that EKF should use for each source on the 23_ekf_config.param file.

8.4 Second Flight: PID VTOL-Quiktune lua script or manual PID tune

If your flight controller can run lua scripts perform a PID lua VTOL-Quicktune. If you have an STM32 F4 or F7 processor that can not run lua scripts perform a manual PID tune instead.

Setup the lua script using:

  1. Connect your flight controller to the PC
  2. Close mission planner, open ArduPilot Methodic Configurator and select your vehicle’s directory
  3. Make sure your PC has internet connection
  4. On ArduPilot Methodic Configurator select 22_quicktune_setup.param on the Current intermediate parameter file: Combobox.
  5. When asked if you want to download the .lua script from internet answer yes.
  6. When asked if you want to upload the .lua script to the FC answer yes.
  7. Read the documentation links inside the 22_quicktune_setup.param documentation
  8. Edit the parameters’ New Value and Change Reason to suit your requirements
  9. Press Upload selected params to FC, and advance to next file button.
  10. Close ArduPilot Methodic Configurator

Perform the flight and afterward:

  1. Connect the flight controller to the PC
  2. On ArduPilot Methodic Configurator select 23_quicktune_results.param on the Current intermediate parameter file: Combobox.
  3. When asked Should the FC values now be copied to the 23_quicktune_results.param file? select Yes.
  4. Press Upload selected params to FC, and advance to next file button.
  5. Close ArduPilot Methodic Configurator

If you are impatient and do not want a fully optimized flight controller jump to Section 13 Productive configuration

9. Standard tuning (optional)

These are the standard tuning steps required for an optimized flight:

9.1 Third flight: MagFit

Now that the Harmonic Notch filter, the throttle controller and PIDs are configured, the third flight will be safer. This flight will be used to calibrate the compass during a realistic operation scenario in the air.

9.1.1 Setup inflight MagFit calibration

Follow these steps before the flight:

  1. On Ardupilot versions < 4.6.0 download the advance-wp.lua scripts from ardupilot github repository, follow Scripted MagFit flightpath generation and put it on the micro SDCard’s APM/scripts folder.
  2. On Ardupilot versions >= 4.6.0 the script is already included.
  3. insert the SD-Card on the flight controller
  4. connect your flight controller to the PC
  5. Make sure your PC has internet connection
  6. On ArduPilot Methodic Configurator select 24_inflight_magnetometer_fit_setup.param on the Current intermediate parameter file: Combobox.
  7. When asked if you want to download the .lua script from internet answer yes.
  8. When asked if you want to upload the .lua script to the FC answer yes.
  9. Read the documentation links inside the 24_inflight_magnetometer_fit_setup.param documentation
  10. Edit the parameters’ New Value and Change Reason to suit your requirements
  11. Press Upload selected params to FC, and advance to next file button.
  12. When asked Should the FC values now be copied to the 25_inflight_magnetometer_fit_results.param file? select No.
  13. Close ArduPilot Methodic Configurator

Perform the MagFit figure-eight flight and land

9.1.2 Calculate inflight MagFit calibration

  1. Download the latest .bin dataflash log file from the micro SDcard’s /APM/LOGS folder
  2. Load it into MAVExplorer using the command line: MAVExplorer.py filename.bin or into the ArduPilot MAGFit in flight compass calibration using an internet browser.
  3. Select the area where the multicopter performed the Figure eight (exclude the takeoff and landing flight sections)
  4. Perform the MagFit calculations. Save the tool-generated file as 25_inflight_magnetometer_fit_results.param in your vehicle’s intermediate parameter file directory.
  5. connect your flight controller to the PC
  6. On ArduPilot Methodic Configurator select 25_inflight_magnetometer_fit_results.param on the Current intermediate parameter file: Combobox.
  7. When asked Should the FC values now be copied to the 25_inflight_magnetometer_fit_results.param file? select Yes.
  8. Press Upload selected params to FC, and advance to next file button.
  9. Close ArduPilot Methodic Configurator

MagFit results

After that repeat the steps described in Section 6.11 ArduPilot Hardware Report.

The report should now look like this:

Hardware-Report after MagFit

9.2 Fourth Flight: PID VTOL-Quiktune lua script or manual PID tune (optional)

If your flight controller can run lua scripts perform a PID lua VTOL-Quicktune. If you have an STM32 F4 or F7 processor that can not run lua scripts perform a manual PID tune instead.

9.2.1 Setup quicktune

Setup the lua script using:

  1. Download the VTOL-quicktune.lua to your PC
  2. connect your flight controller to the PC
  3. Copy the script to your autopilot’s SD card’s APM/scripts directory. If using MP it may be easiest to use the Config, MAVFtp screen.
  4. Close mission planner, open ArduPilot Methodic Configurator and select your vehicle’s directory
  5. On ArduPilot Methodic Configurator select 24_quicktune_setup.param on the Current intermediate parameter file: Combobox.
  6. Read the documentation links inside the 24_quicktune_setup.param documentation
  7. Edit the parameters’ New Value and Change Reason to suit your requirements
  8. Press Upload selected params to FC, and advance to next file button.
  9. When asked Should the FC values now be copied to the 25_quicktune_results.param file? select No.
  10. Close ArduPilot Methodic Configurator

Perform the flight and afterward:

9.2.2 Store quicktune results to file

  1. Connect the flight controller to the PC
  2. On ArduPilot Methodic Configurator select 25_quicktune_results.param on the Current intermediate parameter file: Combobox.
  3. When asked Should the FC values now be copied to the 25_quicktune_results.param file? select Yes.
  4. Press Upload selected params to FC, and advance to next file button.
  5. Close ArduPilot Methodic Configurator

If you are impatient and do not want a fully optimized flight controller jump to Section 13 Productive configuration

9.3 Fifth flight: Evaluate the aircraft tune - part 1

Follow the first part of evaluating the aircraft tune.

  1. On ArduPilot Methodic Configurator select 28_evaluate_the_aircraft_tune_ff_disable.param on the Current intermediate parameter file: Combobox.
  2. Read the documentation links inside the 28_evaluate_the_aircraft_tune_ff_disable.param documentation
  3. Press Upload selected params to FC, and advance to next file button.
  4. Close ArduPilot Methodic Configurator

After landing take a look at the RATE.*out values in the .bin log file, they all should be below 0.1.

If the vehicle is not behaving well, perform a manual PID tune or a lua Quicktune before proceeding.

9.4 Sixth flight: Evaluate the aircraft tune - part 2

Follow the second part of evaluating the aircraft tune.

  1. On ArduPilot Methodic Configurator select 29_evaluate_the_aircraft_tune_ff_enable.param on the Current intermediate parameter file: Combobox.
  2. Read the documentation links inside the 29_evaluate_the_aircraft_tune_ff_enable.param documentation
  3. Press Upload selected params to FC, and advance to next file button.
  4. Close ArduPilot Methodic Configurator

After landing take a look at the RATE.*out values in the .bin log file, they all should be below 0.1.

9.5 Autotune flight(s)

The Autotune is an automated iterative process:

  1. It changes the parameter values of the attitude PID controllers
  2. Tests the overshoot and settling-time of the control loop using the new PID values
  3. If they are within the desired requirements, the process is over. If not, it gets repeated from the beginning

If the battery gets depleted before you can complete the Autotune flight(s), download the latest .bin log file from the micro SDCard directory /APM/LOGS. Take a look at the ATUN messages. They show how the PID values change over time. You should use the latest PID values from the ATUN messages to set the starting point of your next PID Autotune with a fresh battery. But be careful, these new PID values might be unstable and cause your vehicle to crash. To be on the safe side perform the third and fourth flights again according to the instructions above. This way, the Autotune will restart from the partially optimal values it found before the battery got depleted, instead of starting from scratch. An example of the relevant ATUN message data of an interrupted yaw Autotune .bin dataflash log is depicted below:

interrupted yaw Autotune ATUN messages

The correspondence between the PIDs’ initial values and the ATUN message fields is shown in the respective tables for each of the four Autotune axes in the sections below. The tune of the vehicle must be done in the vehicle’s most agile configuration. That is, the vehicle will be at its minimum take-off weight with fully charged batteries. This is why we will do Autotune with multiple flights, one axis per flight.

Typically the quality of the Autotune results for each axis is proportional to the value of the ATC_ANG_RLL_P, ATC_ANG_PIT_P, and ATC_ANG_YAW_P parameters for their respective axis. Also the higher the values, the tighter the tune. If you get low values, improve the hardware and revisit the previous sections to further reduce the vibrations.

Autotuning in low-wind conditions is desirable, but if that is not possible you can increase the AUTOTUNE_AGGR parameter value to 0.110 or even 0.120. That is a workaround and will not produce as good results as low-wind conditions autotune.

We set up the autotune as a flight mode, and as such it will use the underlying ALTHOLD flight mode. If you want to use the LOITER flight mode as the underlying mode during autotune you need to set an RC channel function switch to autotune. Follow the sequence below for tuning each axis as that particular order improves the results.

9.5.1 Roll axis autotune

  1. On ArduPilot Methodic Configurator select 30_autotune_roll_setup.param and upload it to the FC. It will activate the roll axis Autotune.
  2. When asked Should the FC values now be copied to the 31_autotune_roll_results.param file? select No.
  3. Outdoors on a non-windy day (or indoors in a big warehouse like we at IAV do) take off and fly in either AltHold or Loiter flight mode.
  4. At about 2 meters high, select Autotune flight mode in the RC transmitter to engage Autotune.
  5. Use the RC transmitter sticks to correct the vehicle position if it gets too high, too low or too close to obstacles.
  6. Once the Autotune is completed, land and disarm the vehicle without changing the flight mode.
  7. connect the flight controller to the PC
  8. On ArduPilot Methodic Configurator select 31_autotune_roll_results.param.
  9. When asked Should the FC values now be copied to the 31_autotune_roll_results.param file? select Yes.

The autotune might have found a poor solution, here are some indicators of a poor tune:

  1. The resulting ATC_ANG_RLL_P parameter value is smaller than 4.5
  2. The resulting ATC_RAT_RLL_D parameter value is equal to the AUTOTUNE_MIN_D parameter value

If the battery got depleted before Autotune completion, change the initial PID parameters as shown in the table below:

PID parameter name PID parameter value based on the ATUN field
- ATUN.Axis=0
ATC_RAT_RLL_P ATUN.RP
ATC_RAT_RLL_I ATUN.RP
ATC_RAT_RLL_D ATUN.RD
ATC_ANG_RLL_P ATUN.SP
ATC_ACCEL_R_MAX ATUN.ddt

9.5.2 Pitch axis autotune

  1. On ArduPilot Methodic Configurator select 32_autotune_pitch_setup.param and upload it to the FC. It will activate the pitch axis Autotune.
  2. When asked Should the FC values now be copied to the 33_autotune_pitch_results.param file? select No.
  3. Outdoors on a non-windy day (or indoors in a big warehouse like we at IAV do) take off and fly in either AltHold or Loiter flight mode.
  4. At about 2 meters high, select Autotune flight mode in the RC Transmitter to engage Autotune.
  5. Use the RC transmitter sticks to correct the vehicle position if it gets too high, too low or too close to obstacles.
  6. Once the autotune is completed, land and disarm the vehicle without changing the flight mode.
  7. connect the flight controller to the PC
  8. On ArduPilot Methodic Configurator select 33_autotune_pitch_results.param.
  9. When asked Should the FC values now be copied to the 33_autotune_pitch_results.param file? select Yes.

The autotune might have found a poor solution, here are some indicators of a poor tune:

  1. The resulting ATC_ANG_PIT_P parameter value is smaller than 4.5
  2. The resulting ATC_RAT_PIT_D parameter value is equal to the AUTOTUNE_MIN_D parameter value

If the battery got depleted before Autotune completion, change the initial PID parameters as shown in the table below:

PID parameter name PID parameter value based on the ATUN field
- ATUN.Axis=1
ATC_RAT_PIT_P ATUN.RP
ATC_RAT_PIT_I ATUN.RP
ATC_RAT_PIT_D ATUN.RD
ATC_ANG_PIT_P ATUN.SP
ATC_ACCEL_P_MAX ATUN.ddt

9.5.3 Yaw axis autotune

  1. Use ArduPilot Methodic Configurator to edit and upload the 34_autotune_yaw_setup.param file to the FC. It will activate the yaw axis Autotune.
  2. Outdoors on a non-windy day (or indoors in a big warehouse like we at IAV do) take off and fly in either AltHold or Loiter flight mode.
  3. At about 2 meters high, select Autotune flight mode in the RC transmitter to engage Autotune.
  4. Use the RC transmitter sticks to correct the vehicle position if it gets too high, too low, or too close to obstacles.
  5. Once the Autotune is completed, land and disarm the vehicle without changing the flight mode.

You should get something like the 35_autotune_yaw_results.param file.

The autotune might have found a poor solution, here are some indicators of a poor tune:

  1. The resulting ATC_ANG_YAW_P parameter value is smaller than 4.5

If the battery got depleted before Autotune completion, change the initial PID parameters as shown in the table below:

PID parameter name PID parameter value based on the ATUN field
- ATUN.Axis=2
ATC_RAT_YAW_P ATUN.RP
ATC_RAT_YAW_I ATUN.RP * 0.1
ATC_RAT_YAW_FLTE ATUN.RD
ATC_ANG_YAW_P ATUN.SP
ATC_ACCEL_Y_MAX ATUN.ddt

9.5.4 Yaw D axis autotune (optional)

This particular YawD Autotune axis is only relevant for small, agile vehicles.

  1. Use ArduPilot Methodic Configurator to edit and upload the 36_autotune_yawd_setup.param file to the FC.
  2. Outdoors on a non-windy day (or indoors in a big warehouse like we at IAV do) take-off and fly in either AltHold or Loiter flight mode.
  3. At about 2 meters high, select Autotune flight mode in the RC transmitter to engage Autotune.
  4. Use the RC transmitter sticks to correct the vehicle position if it gets too high, too low or too close to obstacles.
  5. Once the Autotune is completed, land and disarm the vehicle without changing the flight mode.

You should get something like the 37_autotune_yawd_results.param file.

Make sure that your resulting ATC_RAT_YAW_D parameter value is different from AUTOTUNE_MIN_D value. If that is not the case then the autotune failed to find a proper ATC_RAT_YAW_D. The cause is probably too high noise values at the input of the Yaw D controller. If the battery got depleted before Autotune completion, change the initial PID parameters as shown in the table below:

PID parameter name PID parameter value based on the ATUN field
- ATUN.Axis=3
ATC_RAT_YAW_P ATUN.RP
ATC_RAT_YAW_I ATUN.RP * 0.1
ATC_RAT_YAW_D ATUN.RD
ATC_ANG_YAW_P ATUN.SP
ATC_ACCEL_Y_MAX ATUN.ddt

9.5.5 Roll and pitch axis re-autotune

Now that the yaw axis is tuned, the autotune should be able to improve the roll and pitch axis tune.

  1. Use ArduPilot Methodic Configurator to edit and upload the 38_autotune_roll_pitch_retune_setup.param file to the FC.
  2. Outdoors on a non-windy day (or indoors in a big warehouse like we at IAV do) take off and fly in either AltHold or Loiter flight mode.
  3. At about 2 meters high, select Autotune flight mode in the RC transmitter to engage Autotune.
  4. Use the RC transmitter sticks to correct the vehicle position if it gets too high, too low or too close to obstacles.
  5. Once the Autotune is completed, land and disarm the vehicle without changing the flight mode.

You should get something like the 39_autotune_roll_pitch_retune_results.param file.

9.6 Performance evaluation flight

As you can see in the picture below, the Stabilize Roll, Pitch and Yaw P gains achieved with this method are high. The maximum stabilize P gain that autotune strives for is 36, and that was achieved in the roll axis! This is a clear indication that the vibration noise filters and the PID control loops are working well together.

Mission Planner's `Extended Tuning` screenshot with our autotune results

After using Autotune to find proper PID parameters, it is time to evaluate the performance of the vehicle’s control loops in real flight.

Follow these steps:

  1. Power on the vehicle and connect it to the PC
  2. Use ArduPilot Methodic Configurator to upload the 28_evaluate_the_aircraft_tune_ff_disable.param file to the FC.
  3. Switch to ALTHOLD flight mode and wait for home location acquisition.
  4. Take-off at around 10m above the ground.
  5. Perform smooth maneuvers using the RC transmitter roll stick.
  6. Perform smooth maneuvers using the RC transmitter pitch stick.
  7. Perform smooth maneuvers using the RC transmitter yaw stick.
  8. Repeat the maneuvers with increasing aggressivity making sure you stay inside the stable envelope of the vehicle.
  9. Land and download the latest .bin log file from /APM/LOGS to your PC
  10. Use ArduPilot’s PID Review Tool to review the PID step response of each PID.
  11. Use ArduPilot Methodic Configurator to upload the 29_evaluate_the_aircraft_tune_ff_enable.param file to the FC.

In our vehicle, we got a transient response of around 60ms in roll and pitch and around 110ms in yaw.

Step response Roll:

Step response Roll

Step response Pitch:

Step response Pitch

Step response Yaw:

Step response Yaw

If you are satisfied with the performance, increase ATC_THR_MIX_MAX to 0.9 (default is 0.5) to increase prioritization of attitude control over throttle. This can reduce the pitch overshoot sometimes seen (especially on copters with large propellers) in AltHold if the vehicle suddenly slows after performing a fast-forward flight. Take a look at the RATE.*out values in the .bin log file, they all should be below 0.1.

Now the standard tuning is complete you can skip to Section 13 Productive Configuration

10. Improve altitude under windy conditions (optional)

10.1 Windspeed Estimation flight(s)

Follow ArduCopter’s airspeed estimation Wiki and/or use the Lua script provided by Yuri in the forum.

In our case, the frontal area looks like this:

frontal area of our drone

and the side area looks like this:

side area of our drone

Divided by 1,000,000 to convert from mm² to m², the frontal area is 0.01097 m² and the side area is 0.01455 m². The weight of our drone is 560g, therefore the ballistic coefficients are

Use ArduPilot Methodic Configurator to edit and upload the 40_windspeed_estimation.param file to the FC.

Now do the flight to collect the data to Calculate the Propeller Drag Coefficient. After that, open the logs with MAVExplorer to get the needed values. Display the absolute values for acceleration in X and Y, as well as GPS speed by inputting graph abs(IMU.AccX) abs(IMU.AccY) GPS.Spd. Then crop it so you only see the tests in AltHold flight mode. It should look like this:

Wind estimation Weathervaning

Note that our test flight was quite noisy but there is enough data to extract. Next crop it so you see one acceleration into the wind and the consecutive deceleration. It should look like this:

Wind estimation rightside

Get the current wind speed, that is the GPS speed when AccY reaches zero and the GPS speed has stabilized. In this case, it is:

Next, get the groundspeed at the start of the test. That is the GPS speed when the vehicle starts to decelerate after the little bit of jitter is over. In this case, it is:

With this information, you can calculate the vehicle’s airspeed, which is:

Next get the maximum acceleration during the test, which is the acceleration at the time of the groundspeed measurement. In this case, it is:

With the air density at the time of testing and the previously calculated ballistic drag coefficient (EK3_DRAG_BCOEF_X for front and back, EK3_DRAG_BCOEF_Y for left and right side) you can now calculate the bluff body drag, which is 1/2 * air density * airspeed^2 / BCOEF. In this case, it is:

With that, you can now calculate the momentum drag, which is max_accel - bluff body drag. In this case, it is:

Now you can calculate the momentum drag coefficient EK3_DRAG_MCOEF, which is momentum drag / airspeed. In this case, it is:

For better accuracy, you should do that for all directions and take the average. In our case, we got:

Note that these are quite high values due to the ducts around the props. For a normal copter with open propellers, it should be in the range of 0.1 to 0.2.

After it is set, do another flight and check that the windspeed and direction are correctly estimated.

10.2 Baro Compensation flight(s)

Follow ArduCopter’s baro compensation Wiki and/or use the Lua script provided by Yuri in the forum.

Use ArduPilot Methodic Configurator to edit and upload the 41_barometer_compensation.param file to the FC.

Now do the flight to collect the data and analyze the logs to see if the barometer is correctly compensated and insensitive to wind.

11. System identification for analytical PID optimization (optional)

This uses Ardupilot’s system identification flight mode to collect data to build a mathematical model of the vehicle that can later be used to further optimize the control loops of the vehicle according to a set of constraints (requirements).

11.1 System Identification Flights

These flights need to be performormed in the total absense of wind. The vehicle PIDs need to be a bit detuned in order to not fully cancel out the injected chirp signals.

11.1.1 Roll rate mathematical model

Use ArduPilot Methodic Configurator to edit and upload the 42_system_id_roll.param file to the FC.

Now do the flight to collect the data for the roll rate system identification.

11.1.2 Pitch rate mathematical model

Use ArduPilot Methodic Configurator to edit and upload the 43_system_id_pitch.param file to the FC.

Now do the flight to collect the data for the pitch rate system identification.

11.1.3 Yaw rate mathematical model

Use ArduPilot Methodic Configurator to edit and upload the 44_system_id_yaw.param file to the FC.

Now do the flight to collect the data for the yaw rate system identification.

11.1.4 Thrust mathematical model

Use ArduPilot Methodic Configurator to edit and upload the 45_system_id_thrust.param file to the FC.

Now do the flight to collect the data for the thrust system identification.

11.2 Analytical Multicopter Flight Controller PID Optimization

This describes how to use IAV’s multi-objective optimization to achieve even better (according to a predefined set of constraints) PID tuning.

One other approach is described by Bill Geyer in his Blog post: Predicting Closed Loop Response For Faster Autotune.

Use ArduPilot Methodic Configurator to edit and upload the 46_analytical_pid_optimization.param file to the FC.

12. Position controller tuning (optional)

12.1 Position controller

The most inner angle rate and angle control loops have been tuned. Now let’s tune the position controller.

Use ArduPilot Methodic Configurator to edit and upload the 47_position_controller.param file to the FC.

12.2 Guided operation without RC transmitter

These are optional, and only make sense if you do beyond visual line-of-sight (BVLOS) autonomous flights using a companion computer.

Use ArduPilot Methodic Configurator to edit and upload the 48_guided_operation.param file to the FC.

12.3 Precision land

These are optional, and only make sense if you have extra hardware on your vehicle to support it.

Use ArduPilot Methodic Configurator to edit and upload the 49_precision_land.param file to the FC.

13. Productive configuration

Some changes should be made for everyday productive operation.

Use ArduPilot Methodic Configurator to edit and upload the 50_everyday_use.param file to the FC.

14. Conclusion

We presented a sequence of small, methodic steps that result in a fully operational and safe drone. Beginning with informed hardware decisions, appropriate hardware configuration and concluding with a finely tuned vehicle equipped with robust, fast-acting control loops. Each step is documented in its own intermediate parameter file, ensuring reproducibility and traceability. Each file is numbered, ensuring that the sequence of steps is clear. The number of test flights was reduced to a minimum, and their order was optimized. This process was developed for our specific multicopter, but it can be tailored to any other ArduPilot vehicle.

PID controller Intermediate parameter file(s) used to configure and tune it
Position Z acceleration 20_throttle_controller.param
Roll rate 31_autotune_roll_results.param, 39_autotune_roll_pitch_retune_results.param
Pitch rate 33_autotune_pitch_results.param, 39_autotune_roll_pitch_retune_results.param
Yaw rate 35_autotune_yaw_results.param, 37_autotune_yawd_results.param
Roll 31_autotune_roll_results.param, 39_autotune_roll_pitch_retune_results.param
Pitch 33_autotune_pitch_results.param, 39_autotune_roll_pitch_retune_results.param
Yaw 35_autotune_yaw_results.param, 37_autotune_yawd_results.param
Position XY velocity 47_position_controller.param

Many thanks to the ArduPilot’s developers and community.

This work has been sponsored by the company I work for IAV GmbH. We provide engineering and consulting for robotic systems including multicopters. Feel free to contact us for help or development support.

Your vehicle is now properly tuned according to AduPilot’s standard procedures and some of IAV GmbH’s know-how.

Enjoy,

Jan Ole Noack

Amilcar do Carmo Lucas