Tune INAV PID‐FF controller for fixedwing - iNavFlight/inav GitHub Wiki
- Manually tuning Rates and Feedforward - How it works
- General ACRO PID tuning
- Tuning ANGLE mode
- LEVEL controller
- Fixedwing I-term Lock
Description of the PID-FF + Rate controller:
When tuned correctly, the FF-gain should do most of the work of pushing the airplane into a turn or climb. Leaving Proportional, Integral and Derivative to make up for slight target error and drift caused by atmospheric disturbances throughout the flight.
[!Important]
Do not underestimate the importance of correctly tuning the stabilization RATES and FEEDFORWARDS to suit your airplanes requirements.
Passing the angular rate target directly to the servo mixer, can reduce control and stabilization processing latency. But if the Rates and Feedforwards are incorrectly tuned, or they are not working in unity with each other. It can instead add extra PID processing time, thus reducing stabilization effectiveness and navigation target accuracy.
The link between Feedforward and Rate
There are four factors which influence the precise maximum rate of rotation that can be achieved on a given fixedwing aircraft.
- The area of the control surfaces.
- The amount of control surface deflection (throws) you have provided in the SMIX or Outputs.
- The planes drag coefficient, mass and inertial resistance to attitude change.
- The specific airspeed your plane is flying at when full
rcDataorrcCommandis applied.
Lets say you have your Roll Rate set to 360°/s. We can look at the two possibilities.
- Will the airplane fall short of reaching the roll Rate setting you have applied?
- Or can the airplane roll even faster than the Rate setting you have applied?
Now looking at how Feedforward pushes to meet that rate target. Feedforward can also work in two ways.
- It is told to push harder than the Rate target your airplane is physically capable of achieving. Meaning the software could even push the control surfaces past the point of peak rotational efficiency, and begin to slow the rate of rotation in some cases, by drag. This is what typically happens on the pitch, if not tuned correctly.
- Or it is not pushing hard enough. And the airplane is falling short of reaching the Rate you have set. Meaning it is not making the Rate target within the time the software expects it to.
So as we can see. Both Feedforward and Rate must work together to reach the maximum rotation rate when tuning. So the software knows exactly how much Feedforward it expects to see or needs to command.
Only when they are both optimally tuned, can the flight software know exactly how much Feedforward is required to be applied to reach the target Rate for precise stabilization and attitude control.
Otherwise it is leaving the axis P-term to make up for either over-shoot or under-shoot of the target rate, effectively adding to instability.
As a result of this. Airplanes that have a lower rate of rotation, generally require a higher Feedforward.
While airplanes that can make a higher rate of rotation, generally require a lower Feedforward.
Tuning of the Rates and Feedforwards can be done more easily via AutoTune, provided it's performed correctly.
However tuning can also be done manually as explained below.
Manually tuning Rates and Feedforward - How it works
While in the process of flying manually. It is beneficial at this time to run Servo Autotrim.
[!Tip] Ensure the control surface servo throws are set correctly before you tune the Rates and Feedforwards manually, or by the Autotune process.
Any adjustments made to the servo Mixer or Output travels after you have tuned the Rates and Feedforwards, will negatively effect performance. Requiring you to run the tuning process again.
In addition Fixedwing Airmode can be enabled withACROmode. Do this before tuning, because the airplane will react differently to the Integral term.
-
Fly in
MANUALmode with themanual_roll_rate,manual_pitch_rateandmanual_yaw_ratesettings set to 100%.
Record DVR footage of the flight, and enable the blackbox to log flight data.
Perform hard rolls, hard loops and one 360° yaw turn. Apply full stick deflection for as long as possible throughout these maneuvers. -
To calculate an axis (approximate) rate from a DVR recording, you'll need to count the number of frames it took for your aircraft to do a complete maneuver (roll/flip/yaw turn), determined by the average FPS of the recording. Then use this formula :
360 / (number_of_frames / FPS).
You can take multiples samples and average them for better accuracy.
You can also use a Python script to help automate the process. -
Typical starting values for Rates, that are suitable for most airplanes are -
Roll = 300°/s
Pitch = 110°/s
Yaw = 70°/s -
Zero out P, I and D gains on the Roll, Pitch and Yaw controllers.
-
Set
tpa_rate = 0 -
Increase FF-gain until you get 90% of full servo throw when having sticks at full throw in
ACROmode, when compared toMANUALmode. -
This is so the FF-gain does most of the work turning the airplane, but leaving some for the P and I gain to work with.
-
For this step it's convenient to have the two modes
MANUALandACROavailable on a switch, so you can easily move between the two, and compare the throws. -
The 90% deflection value can also be calculated by dividing 13950 by the maximum rate for the axis. e.g. 360deg/s maximum roll
13950 / 360 = 38.75FF. For 80% deflection, divide 12400 by the rate. -
Now set some PID gain as a starting point.
fw_p_pitch = 15
fw_i_pitch = 8
fwd_pitch = 2
fw_p_roll = 15
fw_i_roll = 7
fw_i_roll = 3
fw_p_yaw = 10
fw_i_yaw = 2
General ACRO PID tuning
Other settings which can influence the tune are -
-
Looptime can influence PID tuning. It is recommended to tune with the specific looptime you choose, and not change once tuned.
Higher looptime will allow the I-term to respond faster to target error, both in accumulating it (windup) and correcting for overshoot of the error (unwind). But it is not always beneficial for fixedwing platforms. -
Gyro_main_lpf_hz can reduce axis jitter if set lower, by reducing the update rate, which can make stabilization more fluid and less jittery under some wind conditions.
Or you can increase it to reduce filter latency. Which might allow the servo's to react faster to stabilization correction, if tuned tighter using fixedwing airspeed PID attenuation and boost. -
Servo_lpf_hz can be increased to provide less servo latency and a slightly faster reaction time for stabilization response. But it should also be noted that less filtering of the servo signal may cause the brushes in the servo motor to wear faster, leading to premature failure.
Ifservo_lpf_hzis increased. It must be done in sync with servo_pwm_rate.servo_lpf_hzshould not be set higher than half the value of theservo_pwm_rate.
I-term:
If the airplane drifts slightly from center on an axis, once Autotune, AutoLevel and Servo_Autotrim are complete. Increasing the I-gain on that given axis, can reduce the effect.
Be cautious. Too much Integral gain can also cause oscillations, because of the time it takes the accumulated integral error to unwind.
Values should be limited in the mid teens. Accounting for the use of pid_iterm_limit_percent and Fixedwing I-term Lock mentioned below.
P-term:
If you want a greater stabilization response against buffeting from the wind, try increasing the P-gain. But only up to a point.
Too much Proportional gain can cause oscillations as the air-speed increases. This is when you want to apply some Fixedwing APA or TPA, which is required performance tuning in INAV 9.0 and later.
P-term will not be able to completely correct for fixedwing roll axis motion in windy conditions at lower airspeeds, due to processing time and SERVO reaction lag. And that together with limited air flow over the control surfaces.
D-term:
Once the P-gain it tuned to about 80% of its optimal, at a given air speed. Then start applying some Derivative gain in small amounts, to dampen any over correction that is occurring.
Adding D-term can help tighten the response once P-term is optimally tuned. But be cautious of how much you apply.
For optimal servo motor life, 5 should be the limit. But if you don't mind premature servo motor failure. You can push D-term higher to provide a little extra benefit.
After manually tuning your Rates, Feedforwards and Gains. You can reduce the throws a little from their limits, to what suits your stick feel and flight requirements. If you have full servo throw at this stages you would likely overshoot the target deg/s as well, leaving the P-term to do the rest.
Tuning ANGLE mode
-
Auto Level Trim should be used for the purpose of tuning the flight inclination level of the wing, comparing to the Flight Controller boards mounting angle.
However it can also be fine tuned manually if desired. EnterANGLEmode and check if your aircraft fly's straight and level, without climbing or diving slightly.
If it doesn't fly level, your FC is probably not mounted flat relative to the aircraft's Angle of Incidence when flying.
You can adjust it with fw_level_pitch_trim.
Adjusting the board's alignment viaalign_board_roll,align_board_pitchcan also work, but is not recommended unless its a VTOL build, when board alignment can be used for the multicopter profile and level trim for the fixedwing profile. -
If the Roll/Pitch bank angles are too low for your taste, you can adjust them via the
max_angle_inclination_rllandmax_angle_inclination_pit. This will provide greater authority on both axis's, within the full stick deflection range.
If you want the same amount of bank angle in navigation modes, you will also need to increase their values vianav_fw_bank_angle,nav_fw_climb_angle,nav_fw_dive_angle. However, keep in mindnav_fw_bankangles can not be set greater thanmax_angle_inclination.
LEVEL controller
- If you're unhappy with the strength ANGLE based modes return back to level, after the stick is released. You can adjust the P-gain via
fw_p_level. The default value of 20 is optimal. However reducing it can provide a softer feel.
While increasing this value beyond 30 on a fixedwing; generally makes the corresponding axis more jittery when trying to maintain a level attitude in turbulent conditions. fw_i_levelworks as a Low Pass Filter for the LEVEL controllers update rate. Any value greater than 5, is faster than most fixedwings can respond to attitude level correction. Reducing it in some cases to 3 or 2, can help provide a smoother feel.fw_d_leveluses the present rate target and the calculated angle rate target. Which allows for transition between ANGLE (level) and ACRO (rate), to provide HORIZON mode.
When tuning this value. Increase or decrease the setting according to the stick position you want transition to occur. Generally it is better to have transition occur near full stick deflection. Meaning, it's your intent to perform an aerobatic maneuver.
Fixedwing I-term Lock
Version 8.0 and later
This feature solves the problem of I-term accumulation and bounce-back on a Fixedwing platform, when the stick is quickly release back to center, and the airplane still has angular momentum on that axis.
When the pilot moves the sticks, the following happens:
-
P-term and D-term are attenuated with a bell curve. With no attenuation at stick-center, and full attenuation when
fw_iterm_lock_rate_thresholdis met. Its value is a percentage of the maximum axis rotation rate. -
When the rate error rises greater than the
fw_iterm_lock_engage_threshold10% (default). And that error keeps climbing untilfw_iterm_lock_rate_thresholdreaches 40% (default). Then the I-term will become fully attenuated, until the Gyro rate error drops below thefw_iterm_lock_engage_thresholdagain. Or thefw_iterm_lock_time_max_msexpires. -
FF-term is never attenuated. As a result, the airplane feels fully stabilized near stick center, and performs like Manual mode when executing fast maneuvers.
The default settings work fine.
But if you require less attenuation at a higher rate of axis rotation; fw_iterm_lock_rate_threshold can be increased. For example, in the case of 3D airplanes that uses the I-term to help hold axis attitude.
Or on air frames that carry more axis angular momentum, like those with a very high rotation rate or higher wing mass, fw_iterm_lock_engage_threshold can be decreased, or you could add more time to fw_iterm_lock_time_max_ms.
Other tuning tips
- Information on FW navigation tuning can be found here - Navigation PID tuning. This is the place to look if you encounter wandering left or right of the heading target. Or oscillations on the pitch axis while attempting to hold altitude.