Setting the Aircraft Up for Tuning

The following parameters should be set correctly based on the specifications of your aircraft. Each one impacts the quality of the tuning process.

Battery setting

It is very important to ensure that the thrust curve of your VTOL motors is as linear as possible. A linear thrust curve means that changes in the actual thrust produced by a motor is directly proportional to the thrust being demanded by ArduPilot. If your thrust curve is badly non-linear then you will never produce a good tune, and in some cases may end up with such a bad tune that your vehicle can become completely unstable and crash.

There are 3 common causes of a non-linear thrust curve.

  • voltage sag as throttle is increased.

  • incorrect end-point setup in the PWM range you use to your ESCs (see “Motors setup” below)

  • non-linearity in the thrust produced by your propeller, ESC and motor combination

Start with setting up the voltage range to cope with voltage sag. Parameters used to linearise your motor thrust curve.

  • MOT_BAT_VOLT_MAX: 4.2v x No. Cells

  • MOT_BAT_VOLT_MIN: 3.3v x No. Cells

  • MOT_OPTIONS = 0 (default). The default is to use sag compensated voltage for the above and during tuning computations. It can be set to 1 to use raw voltage instead of sag compensated voltage, which may improve tuning results for light vehicles.

Next setup the thrust expo. If you are setting up a professional aircraft then you should invest in a thrust stand so you can accurately measure the true thrust for your motor/ESC/propeller combination as you vary the throttle. Then you will adjust the expo value along with the endpoints (given by motors setup below) so that the thrust between the endpoints is as linear as possible. Do not trust manufacturer data for the thrust curve as they are frequently inaccurate. See Motor Thrust Scaling for details on thrust scaling.

If you are setting up a hobby grade vehicle then you can use the graph below to estimate the correct MOT_THST_EXPO value for your aircraft.

  • MOT_THST_EXPO: 0.55 for 5 inch props, 0.65 for 10 inch props, 0.75 for 20 inch props (or larger). This parameter should be derived by thrust stand measurements for best results (don’t trust manufacturer data).

../_images/tuning-process-instructions-1.hires.png

Motors setup

The motor parameters define the PWM output range sent to the ESCs. This is critical to ensure that the entire range of throttle values used in flight is within the linear range of your propulsion system.

Parameters used to define the output range sent to the ESC.

  • MOT_PWM_MAX: Check ESC manual for fixed range or 2000us

  • MOT_PWM_MIN: Check ESC manual for fixed range or 1000us

  • MOT_SPIN_ARM: use the motor test feature to determine a value which will reliably start the motors spinning at a low rpm as an indication of the armed state.

  • MOT_SPIN_MAX: 0.95

  • MOT_SPIN_MIN: use the motor test feature and motor test data, if available, to set the lower range of linear thrust. The default value is usually adequate for hobby uses.

  • MOT_THST_HOVER: 0.25 or below the expected actual hover thrust percentage (lower is safe)

PID Controller Initial Setup

The settings below are meant to get your PID controller acceleration and filter settings into the right approximate range for your vehicle. These parameters are critical to the tuning process. The PID controller default values for axis P/D/I values are usually safe for first test hovers of most vehicles.

  • INS_ACCEL_FILTER: 10Hz

  • INS_GYRO_FILTER: 80Hz for 5 inch props, 40Hz for 10 inch props, 20Hz for 20 inch props (or larger)

  • ATC_ACCEL_P_MAX: 110000 for 10 inch props, 50000 for 20 inch props, 20000 for 30 inch props

  • ATC_ACCEL_R_MAX: 110000 for 10 inch props, 50000 for 20 inch props, 20000 for 30 inch props

  • ATC_ACCEL_Y_MAX: 27000 for 10 inch props, 18000 for 20 inch props, 9000 for 30 inch props

For Copter-4.1 (and later):

../_images/tuning-process-instructions-2.hires.png ../_images/tuning-process-instructions-3.hires.png ../_images/tuning-process-instructions-4.hires.png

Mission Planner Helper

A tab under SETUP/Mandatory Hardware/Initial Parameter Setup is provided in Mission Planner to setup the above parameters easily.

../_images/mp-initial-copter-param-setup.png