Last month we finally merged the new fixed wing control code slated for the ArduPilot plane 4.1 release. This provides a major improvement in several areas:
- much better manual PID tuning, with clearer parameters and much improved filtering
- new fixed wing AUTOTUNE system which produces a much better tune for a wider range of aircraft
The key change in the PIDs is we are switching to use the same PID code that is used for VTOL aircraft in ArduPilot. This leverages the great work that @Leonardthall has done to improve that PID system for the 4.1 release and gives us a common framework.
Old PID System
The old fixed wing PID system had some unusual properties that were left over from the very early days of ArduPilot. Specifically, the feed-forward gain was calculated using a combination of the P, I, D and time-constant. This was originally done to preserve parameter value behaviour for people running very early versions of ArduPilot. That odd feed-forward calculation did work, but made it harder to properly tune the aircraft for someone who does understand how PIDs work. For example, if you increased RLL2SRV_D in the old code to get a bit more damping then that would also, as a side effect, decrease the feed-forward gain, which is probably not what the user really wanted.
New PID System
The new PID system uses new names for the rate gains. For example, the full set of roll controller gains are now:
- RLL2SRV_RMAX
- RLL2SRV_TCONST
- RLL_RATE_FF
- RLL_RATE_P
- RLL_RATE_I
- RLL_RATE_D
- RLL_RATE_FLTD
- RLL_RATE_FLTE
- RLL_RATE_FLTT
- RLL_RATE_IMAX
- RLL_RATE_SMAX
The same parameters are available for pitch, but with a PTCH prefix instead of RLL.
The RMAX and TCONST parameters are the same as before, and are the key parameters for determining the feel of the tune. If you want a very sharp response then you need a high RMAX and a low TCONST. For a gentle tune (eg. a glider) use low RMAX and high TCONST.
The rate PID itself now has 4 gain parameters, FF, P, I and D. In nearly all fixed wing aircraft the FF (feed-forward) term dominates, and is the most important parameter to get right. Luckily you can read the right FF value from any log where the pilot has commanded a sustained rate in the axis of the FF (eg. commanded a full right roll, or pitch up).
The P and D terms are the correction terms, and they are the ones that will most likely drive an oscillation if you push them too high. That is why we have a new slew limiter feature that can detect this oscillation and automatically back off the P and D components of the PID to reduce the oscillation.
New Fixed Wing AUTOTUNE Mode
Along with the new PID system we also have a new AUTOTUNE mode. This is a big improvement over the old AUTOTUNE, and is able to correctly setup your FF parameters as well as P, I and D. It should work on a much wider range of aircraft than the old AUTOTUNE.
As always, please report any issues you find with the new code! If you’d like to try it then just load the ‘latest’ firmware and go for it! Post any issues here.
When you update it will auto-convert your old PIDs to the new system.
PID Calculator
I have put a PID calculator for converting between the old and new system here: ArduPilot Plane 4.1.x PID Calculator