APM_Control: Added alternate tuning method for roll and pitch loops
The alternate tuning method for roll and pitch will give a better results, but comes with more risk as it will result in a larger rate feedback gain
This commit is contained in:
parent
2c29186b03
commit
3034a9fab2
@ -29,10 +29,20 @@ Initial assessment:
|
||||
|
||||
Roll control tuning:
|
||||
|
||||
Basic:
|
||||
Basic Method 1:
|
||||
This method is the simplest and is basically the same as tuning the old PID loops, but won't give the best result
|
||||
|
||||
1) With the model in FBW-A mode, put in a rapid bank angle demand, hold it and release. Do the same in the other direction. You want the model to roll quickly and smoothly to the new bank angle and back again without overshoot or any wing 'waggle'. If the roll response is too slow, then progressively increase the CTL_RLL_K_P parameter in increments of 0.1 until it starts to overshoot and wing rock a little.
|
||||
2) Now increase the CTL_RLL_K_D gain in small increments of 0.01 until the overshoot or waggle goes away. If it hasn't worked by the time you have reached a value of 0.1 for CTL_RLL_K_D, DONT go any further - you need to reduce CTL_RLL_K_P.
|
||||
|
||||
Basic Method 2:
|
||||
This method gives the best result, but requires more caution because step 2) can produce a high frequency instability that unless reversion back to manual is done quickly, could overstress the plane.
|
||||
|
||||
1) Set CTL_RLL_K_D to [TBD] and CTL_RLL_K_P to 0.0
|
||||
2) Increase CTL_RLL_K_D in small amounts from the default value of [TBD] until it it starts to oscillate, then halve it.
|
||||
3) Increase CTL_RLL_OMEGA from the dfault value of 1.0 if necessary to give the desired responsiveness. If the roll starts to overshoot, reduce it.
|
||||
4) Increase CTL_RLL_K_P from the default value of 0 to improve the initial response.
|
||||
|
||||
Advanced:
|
||||
1) Select the tuning box on the bottom of the Mission planers Flight Data page. You should get a scrolling black window above the map. Double click in the black window and you should get a list of parameters to plot. Change the selection until you have the roll and nav_roll plotted. Nav_roll is the demand and roll is the response. You can use this to look for overshoot and other behavior that isn't so obvious from the ground looking at the model.
|
||||
2) Check for any steady offset between nav-roll and roll. If there is one you can set the CTL_RLL_K_I to a small value (say 0.01) which will allow the control loop to slowly trim the aileron demand to remove the steady error. If you want it to trim faster, you can increase the value for this gain.
|
||||
@ -41,14 +51,25 @@ Advanced:
|
||||
|
||||
Pitch Control Tuning:
|
||||
|
||||
Basic:
|
||||
Basic Method 1:
|
||||
This method is the simplest and is basically the same as tuning the old PID loops, but won't give the best result
|
||||
|
||||
1) With the model in FBW-A mode and the throttle at the cruise position, put in a pitch angle demand, hold it and release. Do the same in the other direction. You want the model to pitch smoothly to the new pitch angle and back again without overshoot or proposing. If the pitch response is too slow, then progressively increase the CTL_PTCH_K_P parameter in increments of 0.1 until it starts to overshoot and porpoise a little.
|
||||
2) Now increase the CTL_RLL_K_D gain in small increments of 0.01 until the overshoot or porpoise goes away. If it hasn't worked by the time you have reached a value of 0.1 for CTL_PTCH_K_D, DONT go any further - you need to reduce CTL_PTCH_K_P.
|
||||
3) Now roll the model to maximum bank in each direction. The nose should stay fairly level during the turns without significant gain or loss of altitude. Some loss of altitude during sustained turns at constant throttle is expected, because the extra drag of turning slows the model down which will cause a mild descent. If the model gains height during the turns then you need to reduce the CTL_PTCH_K_RLL by small increments of 0.01 from the default value of 1.0. If the model descends immediately when the model banks (a mild descent later in the turn when the model slows down is normal as explained earlier) then increase the CTL_PTCH_K_RLL by small increments of 0.01 from the default value of 1.0. If you need to change the CTL_PTCH_K_RLL parameter outside the range from 0.8 to 1.2 then something is likely wrong with either the earlier tuning of your pitch loop, your airspeed calibration or you APM's bank angle estimate.
|
||||
|
||||
Basic Method 2:
|
||||
This method gives the best result, but requires more caution because step 2) can produce a high frequency instability that unless reversion back to manual is done quickly, could overstress the plane.
|
||||
|
||||
1) Set CTL_PTCH_K_D to [TBD] and CTL_RLL_K_P to 0.0
|
||||
2) Increase CTL_PTCH_K_D in small amounts from the default value of [TBD] until it it starts to oscillate, then halve it.
|
||||
3) Increase CTL_PTCH_OMEGA from the dfault value of 1.0 if necessary to give the desired responsiveness. If the pitch starts to overshoot, reduce it.
|
||||
4) Increase CTL_PTCH_K_P from the default value of 0 to improve the initial response.
|
||||
|
||||
Advanced:
|
||||
1) The maximum nose down and nose up pitch rate in degrees/second can be constrained by setting the CTL_PTCH_RMAX_D and CTL_PTCH_RMAX_U parameters to a value other than 0. These parameters These can be used to limit the amount of g produced during a pull-up or push down.
|
||||
2) The time constant of the pitch control lop can be reduced by increasing the CTL_PTCH_OMEGA parameter from the default value of 1.0. this will give a 'snappier' pitch response, but does mean that the noise in the demands from the airspeed control loop can cause unwanted pitch motion.
|
||||
3) Increase CTL_PTCH_K_I from a default value of zero until steady state errors in pitch angle are removed (you will need to monitor the nav_pitch and pitch in the tuning graphs window to do this).
|
||||
|
||||
Yaw Control Tuning:
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user