AutoTune

AutoTune attempts to automatically tune the Stabilize P, Rate P and D, and maximum rotational accelerations to provide the highest response without significant overshoot. Copter needs to be “basically” flyable in AltHold mode before attempting to use AutoTune as the feature needs to be able to “twitch” the copter in the roll and pitch axis.

Warning

AutoTune is not always able to determine a good tune for the vehicle and may result in gains that lead to an unflyable vehicle that may crash. Please follow the Tuning Process Instructions before attempting to use AutoTune. After following those instructions, and have evaluated your initial tune, should to try AutoTune.

Note

using QuikTune before AUTOTUNE, AND setting up the noise notch filtering, see Managing Gyro Noise with the Dynamic Harmonic Notch Filters, is highly recommended in order to get the best tune and avoid possible crashes when using AUTOTUNE.

There are number of problems that can prevent AutoTune from providing a good tune including:

  • Strong wind

  • High levels of gyro noise

  • Non-linear ESC response caused by the incorrect value of MOT_THST_EXPO

  • Flexible frame or payload mount

  • Overly flexible vibration isolation mount

  • Very low setting for MOT_SPIN_MIN

  • Overloaded propellers or motors

Setup before flying in AutoTune mode

  1. Set up one flight mode switch position to be AltHold.

  2. Set an RC channel Auxiliary Function switch or an Auxiliary Function Switch (prior to version 4.0) to AutoTune to allow you to turn the auto tuning on/off with a switch.

Note

you can also set the AUTOTUNE flight mode as a mode on your flight mode switch to activate AutoTune

  1. Remove the camera gimbal or any other parts of the frame that could wobble in flight

  2. Select which combination of axes (roll, pitch, yaw) you wish to tune using the AUTOTUNE_AXES parameter

  3. Set the autotune’s aggressiveness using the AUTOTUNE_AGGR parameter (0.1=agressive, 0.075=medium, 0.050=weak), normally start with the default 0.1.

  4. For large copters (with props at least 13inch or 33cm diameter) set the Rate Roll and Pitch filters to 10hz, these are: ATC_RAT_RLL_FLTT, ATC_RAT_RLL_FLTD, ATC_RAT_PIT_FLTT, ATC_RAT_PIT_FLTD, (in Copter-3.4 they are ATC_RAT_RLL_FILT and ATC_RAT_PIT_FILT)

  5. It is recommended to enable battery voltage scaling of PID gains

How to invoke AutoTune

  1. Wait for a calm day and go to a large open area.

  2. Ensure the ch7 or ch8 switch, if used, is in the LOW position.

  3. Take off and put the copter into AltHold mode at a comfortable altitude.

  4. Face the vehicle so that it will twitch at 90degrees from the direction the wind is blowing (i.e. if tuning Roll first, point the vehicle into the wind)

    ../_images/autotune_copterwind.png
  5. Set the ch7/ch8 switch to the HIGH position, or switch to AUTOTUNE mode, to engage auto tuning:

    • You will see it twitch about 20 degrees left and right for a few minutes, then it will repeat forward and back.

    • Use the roll and pitch stick at any time to reposition the copter if it drifts away (it will use the original PID gains during repositioning and between tests). When you release the sticks it will continue auto tuning where it left off.

    • Move the ch7/ch8 switch into the LOW position, or change flight mode if using AUTOTUNE flight mode, at any time to abandon the autotuning and return to the origin PIDs.

    • Make sure that you do not have any trim set on your transmitter or the autotune may not get the signal that the sticks are centered.

  6. When the tune completes the copter will change back to the original PID gains.

  7. Put the ch7/ch8 switch into the LOW position and then back to the HIGH position to test the tuned PID gains, or if using the AUTOTUNE flight mode, switch out and then back into that mode.

  8. Put the ch7/ch8 switch into the LOW position, or switch out of AUTOTUNE flight mode, to fly using the original PID gains.

  9. If you are happy with the autotuned PID gains, leave the ch7/ch8 switch in the HIGH position, or switch back into AUTOTUNE flight mode and land and disarm to save the PIDs permanently.

    If you DO NOT like the new PIDS, switch ch7/ch8 LOW or out of AUTOTUNE flight mode, to return to the original PIDs. The gains will not be saved when you disarm.

If you find after performing an AutoTune that the vehicle feels overly twitchy when flying Stabilize, AltHold or PosHold (but ok in more autonomous modes like Loiter, RTL, Auto) try increasing the ATC_INPUT_TC parameter to 0.25. This smooths out the pilot’s input. Alternatively try reducing the AUTOTUNE_AGGR parameter (it should always be in the range 0.05 to 0.10) and try again.

If the vehicle feels sloppy after the AutoTune, try increasing the AUTOTUNE_AGGR parameter as high as 0.10 and attempt the autotune again.

Invoke AutoTune with Position Hold

Warning

A better tune can often be achieved by invoking AutoTune from AltHold as described above instead of from Loiter or PosHold as described below. Using AUTOTUNE flight mode also has this possible disadvantage.

AutoTune performs a weak position hold if invoked from Loiter or PosHold flight modes (as opposed to AltHold) while doing an autotune. If using the AUTOTUNE flight mode, this weak position hold is also used.

../_images/autotune_from_loiter.png
  • The vehicle will gently lean (up to 10 degrees) towards a “target point” which is initially set to the vehicle’s location at the moment AutoTune was invoked.

  • The pilot can reposition the vehicle using the roll, pitch, yaw or throttle sticks. The target position will be reset to the vehicle’s location at the moment the pilot releases the roll and pitch sticks.

  • The altitude is maintained with the altitude hold controller so the vehicle will attempt to hold its current altitude when the sticks are placed with 10% of mid-throttle. It will climb or descend at up to 2.5m/s (this speed is adjustable with the PILOT_SPEED_UP and PILOT_SPEED_DN parameters). The acceleration used to establish these speeds is set by PILOT_ACCEL_Z.

  • To twitch perpendicular to the wind direction, the vehicle may suddenly rotate in either direction up to 90 degrees as it drifts 5m (or more) from the target location.

  • If there is little or no wind, the vehicle’s gentle position control may mean it moves back and forth, ping-ponging around the target point changing yaw each time it strays more than 5m from the target. In these cases, it may be more comfortable to revert to the simpler AltHold-based AutoTune.

If AutoTune fails

If AutoTune has failed you will need to do a manual tune.

Some signs that AutoTune has been successful are (besides DataFlash logs and Ground Control Station messages):

AutoTune will attempt to tune each axis as tight as the aircraft can tolerate. In some aircraft, this can be unnecessarily responsive. A guide for most aircraft:

These values should only be changed if AutoTune produces higher values. Small aerobatic aircraft may prefer to keep these values as high as possible.

Additional Notes

  • In Copter-3.3 (and higher) AutoTune can be setup as a flight mode. Switching into or out of the AutoTune flight mode responds in the same way as raising or lowering a ch7/ch8 aux switch high assigned to the AutoTune function.

  • In Copter-4.4 (and higher) AutoTune can tune the yaw D axis.

  • AUTOTUNE_AXES allows control of which axes are to be tuned. This is useful if the vehicle’s battery life is not long enough to complete all 4-axis. “1” = tune roll, “2” = tune pitch, “4” = tune yaw, “8” = tune yaw D. Add these numbers together to tune multiple axes in a single session (i.e. “15” = tune all axes)

  • AUTOTUNE_AGGR: Should be in the range of 0.05 to 0.10. Higher values will produce a more aggressive tune but sometimes results in gains that are too high. More specifically this parameter controls the threshold for D-term bounce back and P-term overshoot. This affects the tuning noise immunity (a higher value is more tolerant to flex in the frame or other disturbances that could trick the tuning algorithm). High values also leads to a tune that rejects external disturbances better. Lower values result in a tune that is more responsive to pilot input.

  • The full list of parameters that may be updated by AutoTune

  • After you have a good tune, you may wish to 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. In this situation, wind catches under the propellers providing lift but also disturbs the vehicle’s attitude leading to a conflict between throttle and attitude control. The danger in increasing this parameter’s value is that if the rate gains are later raised so high that the vehicle oscillates badly it may be difficult for the vehicle to descend (because it will prioritize trying to correct the attitude oscillations and never reduce throttle sufficiently).

  • AutoTune can request very large and fast changes in outputs to the motors which can cause ESC sync issues especially when using SimonK firmware and/or low KV motors (under 500KV). See this video showing a test which recreates a sync problem.

  • For best results, the copter shouldn’t be allowed to build up too much horizontal speed. This can be prevented by applying a quick correction between tests (twitches) to stop the vehicle from flying too fast.

  • Be advised that AutoTune will engage from Stabilize, so don’t accidentally flip your AutoTune switch until you are in AltHold and ready to begin the procedure.

  • As a general rule, for Pitch and Roll, P and I should be equal, and D should be 1/10th P. For Yaw, I should be 1/10th P and D = 0, in most cases.

Common Problems

  • If the vehicle will not start tuning (i.e. it won’t twitch) even though it is in AutoTune mode then the problem is likely that the roll, pitch, yaw or throttle sticks are not exactly in the middle. It may help to increase the deadzone on the RC input by increasing RC1_DZ, RC2_DZ, RC3_DZ and RC4_DZ to 50 (or higher).

  • If the AutoTune produces an overly twitchy vehicle try reducing the AUTOTUNE_AGGR parameter (should never be below 0.05) and perform the AutoTune again.

  • If the AutoTune produces a sloppy vehicle, try increasing the AUTOTUNE_AGGR parameter (should never be above 0.1) and perform the AutoTune again.

Tip

When reporting issues with AutoTune please include a description of your frame and a .bin dataflash log of the flight.

Dataflash logging

ATUN (auto tune overview) and ATDE (auto tune details) messages are written to the dataflash logs. Some details of the contents of those messages can be found on the Downloading and Analyzing Data Logs in Mission Planner wiki page.

Ground Control Station Messages

For each axis, there are several phases to the tune. Rate PIDs are adjusted first, then ANGLE parameters. Progress messages during these phases are sent to the GCS (and recorded in the Dataflash logs).

The typical sequence during tuning might be:

09:09:33       AutoTune: Twitch
09:09:34       AutoTune: (P) Rate P Up\
09:09:34       AutoTune: WFL (Rate(P)) (15.13040 > 10.00000)
09:09:34       AutoTune: p=0.052298 d=0.005232
09:09:34       AutoTune: success 1/4

This is during Pitch Rate P adjustment, indicating a twitch is about to happen as the P is being tried at an increased value of 0.052298, but first, it is waiting until it gets back to level from the last twitch (WFL= Waiting for level), and then it reports that the result of this twitch is within targets and successful. But this has to occur 4 times in a row, before moving on to the next phase.

Note

During the YAW rate phase of tuning, the messages will show a value for “d” that is not ATC_RAT_YAW_D, which is usually 0, but rather it’s the value of ATC_RAT_YAW_FLTE, that is being changed.

Anytime the process is interrupted by pilot stick movements, the

09:09:38       AUTOTUNE: pilot overrides active

message appears.

If you stopped the tune and dis-armed while still in AUTOTUNE, and an axis tune has been completed, you will get a message showing that the new gains have been saved for that axis. If there is not a message to this effect, but think you finished at least one axis, then you probably dis-armed while not in AUTOTUNE mode, and did not actually save them.

09:19:48       AutoTune: Saved gains for Pitch

Tip

If you do happen to accidentally discard a session’s AUTOTUNE values by disarming when not in AUTOTUNE, you can examine the dataflash log for the GCS messages it sent during the tune and manually set them on the bench.


../_images/banner-freespace.png