mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
APM_control: Modified gain definitions for roll and pitch controllers so PID gains behave like previous servo PIDS
Gain definitions in roll and pitch controllers were updated previously so that the old PID tuning values could be transferred across. Updated tuning guide for revised gain definition.
This commit is contained in:
parent
6e0f1f56de
commit
716c124f73
@ -16,37 +16,38 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
|
||||
|
||||
// @Param: OMEGA
|
||||
// @DisplayName: Pitch to rate gain
|
||||
// @Description: This is the gain from pitch angle error to demanded pitch rate. It controls the time constant from demanded to achieved pitch angle. For example if a time constant from demanded to achieved pitch of 0.5 sec was required, this gain would be set to 1/0.5 = 2.0. A value of 1.0 is a good default and will work with nearly all models. Advanced users may want to increase this to obtain a faster response.
|
||||
// @Range: 0.8 2.5
|
||||
// @Param: T_CONST
|
||||
// @DisplayName: Pitch Time Constant
|
||||
// @Description: This controls the time constant in seconds from demanded to achieved pitch angle. A value of 0.7 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
|
||||
// @Range: 0.4 1.0
|
||||
// @Units: seconds
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OMEGA", 0, AP_PitchController, _kp_angle, 1.0),
|
||||
AP_GROUPINFO("T_CONST", 0, AP_PitchController, _tau, 0.7),
|
||||
|
||||
// @Param: K_P
|
||||
// @DisplayName: Pitch to elevator gain
|
||||
// @Description: This is the gain from demanded pitch rate to demanded elevator. Provided CTL_PTCH_OMEGA is set to 1.0, then this gain works the same way as the P term in the old PID (PTCH2SRV_P) and can be set to the same value.
|
||||
// @Range: 0.1 2
|
||||
// @DisplayName: Proportional Gain
|
||||
// @Description: This is the gain from pitch angle to elevator. This gain works the same way as PTCH2SRV_P in the old PID controller and can be set to the same value.
|
||||
// @Range: 0.1 1.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_P", 1, AP_PitchController, _kp_ff, 0.4),
|
||||
AP_GROUPINFO("K_P", 1, AP_PitchController, _K_P, 0.4),
|
||||
|
||||
// @Param: K_D
|
||||
// @DisplayName: Pitch damping gain
|
||||
// @Description: This is the gain from pitch rate error to demanded elevator. This adjusts the damping of the pitch control loop. It has the same effect as the D term in the old PID (PTCH2SRV_D) but without the large spikes in servo demands. This will be set to 0 as a default. Some airframes such as flying wings that have poor pitch damping can benefit from a small value of up to 0.1 on this gain term. This should be increased in 0.01 increments as to high a value can lead to a high frequency pitch oscillation that could overstress the airframe.
|
||||
// @DisplayName: Damping Gain
|
||||
// @Description: This is the gain from pitch rate to elevator. This adjusts the damping of the pitch control loop. It has the same effect as PTCH2SRV_D in the old PID controller and can be set to the same value, but without the spikes in servo demands. This gain helps to reduce pitching in turbulence. Some airframes such as flying wings that have poor pitch damping can benefit from increasing this gain term. This should be increased in 0.01 increments as too high a value can lead to a high frequency pitch oscillation that could overstress the airframe.
|
||||
// @Range: 0 0.1
|
||||
// @Increment: 0.01
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_D", 2, AP_PitchController, _kp_rate, 0.0),
|
||||
AP_GROUPINFO("K_D", 2, AP_PitchController, _K_D, 0.0),
|
||||
|
||||
// @Param: K_I
|
||||
// @DisplayName: Pitch integrator gain
|
||||
// @Description: This is the gain for integration of the pitch rate error. It has essentially the same effect as the I term in the old PID (PTCH2SRV_I). This can be set to 0 as a default, however users can increment this to make the pitch angle tracking more accurate.
|
||||
// @Range: 0 0.3
|
||||
// @Increment: 0.01
|
||||
// @DisplayName: Integrator Gain
|
||||
// @Description: This is the gain applied to the integral of pitch angle. It has the same effect as PTCH2SRV_I in the old PID controller and can be set to the same value. Increasing this gain causes the controller to trim out constant offsets between demanded and measured pitch angle.
|
||||
// @Range: 0 0.5
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_I", 3, AP_PitchController, _ki_rate, 0.0),
|
||||
AP_GROUPINFO("K_I", 3, AP_PitchController, _K_I, 0.0),
|
||||
|
||||
// @Param: RMAX_U
|
||||
// @DisplayName: Pitch up max rate
|
||||
@ -54,7 +55,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
|
||||
// @Range: 0 100
|
||||
// @Units: degrees/second
|
||||
// @Increment: 1
|
||||
// @User: User
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RMAX_U", 4, AP_PitchController, _max_rate_pos, 0.0),
|
||||
|
||||
// @Param: RMAX_D
|
||||
@ -63,7 +64,7 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = {
|
||||
// @Range: 0 100
|
||||
// @Units: degrees/second
|
||||
// @Increment: 1
|
||||
// @User: User
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RMAX_D", 5, AP_PitchController, _max_rate_neg, 0.0),
|
||||
|
||||
// @Param: K_RLL
|
||||
@ -99,6 +100,11 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
||||
if(_ahrs == NULL) return 0;
|
||||
float delta_time = (float)dt * 0.001f;
|
||||
|
||||
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
|
||||
// No conversion is required for K_D
|
||||
float kp_ff = max((_K_P - _K_I * _tau) * _tau - _K_D , 0);
|
||||
float ki_rate = _K_I * _tau;
|
||||
|
||||
// Calculate offset to pitch rate demand required to maintain pitch angle whilst banking
|
||||
// Calculate ideal turn rate from bank angle and airspeed assuming a level coordinated turn
|
||||
// Pitch rate offset is the component of turn rate about the pitch axis
|
||||
@ -131,7 +137,7 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
||||
int32_t angle_err = angle - _ahrs->pitch_sensor;
|
||||
|
||||
// Calculate the desired pitch rate (deg/sec) from the angle error
|
||||
float desired_rate = angle_err * 0.01f * _kp_angle;
|
||||
float desired_rate = angle_err * 0.01f / _tau;
|
||||
|
||||
// limit the maximum pitch rate demand. Don't apply when inverted
|
||||
// as the rates will be tuned when upright, and it is common that
|
||||
@ -161,9 +167,9 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
||||
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
|
||||
if (!stabilize) {
|
||||
//only integrate if gain and time step are positive and airspeed above min value.
|
||||
if ((fabsf(_ki_rate) > 0) && (dt > 0) && (aspeed > float(aspd_min)))
|
||||
if ((ki_rate > 0) && (dt > 0) && (aspeed > float(aspd_min)))
|
||||
{
|
||||
float integrator_delta = rate_error * _ki_rate * scaler * delta_time;
|
||||
float integrator_delta = rate_error * ki_rate * scaler * delta_time;
|
||||
if (_last_out < -45) {
|
||||
// prevent the integrator from increasing if surface defln demand is above the upper limit
|
||||
integrator_delta = max(integrator_delta , 0);
|
||||
@ -181,7 +187,7 @@ int32_t AP_PitchController::get_servo_out(int32_t angle, float scaler, bool stab
|
||||
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
||||
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
||||
// This is because acceleration scales with speed^2, but rate scales with speed.
|
||||
_last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
||||
_last_out = ( (rate_error * _K_D) + _integrator + (desired_rate * kp_ff) ) * scaler;
|
||||
|
||||
// Convert to centi-degrees and constrain
|
||||
return constrain_float(_last_out * 100, -4500, 4500);
|
||||
|
@ -22,10 +22,10 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_Float _kp_angle;
|
||||
AP_Float _kp_ff;
|
||||
AP_Float _kp_rate;
|
||||
AP_Float _ki_rate;
|
||||
AP_Float _tau;
|
||||
AP_Float _K_P;
|
||||
AP_Float _K_I;
|
||||
AP_Float _K_D;
|
||||
AP_Int16 _max_rate_pos;
|
||||
AP_Int16 _max_rate_neg;
|
||||
AP_Float _roll_ff;
|
||||
|
@ -10,52 +10,52 @@
|
||||
|
||||
#include <AP_Math.h>
|
||||
#include <AP_HAL.h>
|
||||
|
||||
#include "AP_RollController.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = {
|
||||
// @Param: OMEGA
|
||||
// @DisplayName: Roll rate gain
|
||||
// @Description: This is the gain from pitch angle error to demanded pitch rate. It controls the time constant from demanded to achieved pitch angle. For example if a time constant from demanded to achieved pitch of 0.5 sec was required, this gain would be set to 1/0.5 = 2.0. A value of 1.0 is a good default and will work with nearly all models. Advanced users may want to increase this to obtain a faster response.
|
||||
// @Range: 0.8 2.5
|
||||
// @Param: T_CONST
|
||||
// @DisplayName: Pitch Time Constant
|
||||
// @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.7 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve.
|
||||
// @Range: 0.4 1.0
|
||||
// @Units: seconds
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OMEGA", 0, AP_RollController, _kp_angle, 1.0),
|
||||
AP_GROUPINFO("T_CONST", 0, AP_RollController, _tau, 0.7),
|
||||
|
||||
// @Param: K_P
|
||||
// @DisplayName: Roll demand gain
|
||||
// @Description: This is the gain from demanded roll rate to demanded aileron. Provided CTL_RLL_OMEGA is set to 1.0, then this gain works the same way as the P term in the old PID (RLL2SRV_P) and can be set to the same value.
|
||||
// @Range: 0.1 2
|
||||
// @DisplayName: Proportional Gain
|
||||
// @Description: This is the gain from bank angle to aileron. This gain works the same way as the P term in the old PID (PTCH2SRV_P) and can be set to the same value.
|
||||
// @Range: 0.1 1.0
|
||||
// @Increment: 0.1
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_P", 1, AP_RollController, _kp_ff, 0.4),
|
||||
AP_GROUPINFO("K_P", 1, AP_RollController, _K_P, 0.4),
|
||||
|
||||
// @Param: K_D
|
||||
// @DisplayName: Roll derivative gain
|
||||
// @Description: This is the gain from pitch rate error to demanded elevator. This adjusts the damping of the roll control loop. It has the same effect as the D term in the old PID (RLL2SRV_D) but without the large spikes in servo demands. This will be set to 0 as a default. This should be increased in 0.01 increments as too high a value can lead to high frequency roll oscillation.
|
||||
// @DisplayName: Damping Gain
|
||||
// @Description: This is the gain from roll rate to aileron. This adjusts the damping of the roll control loop. It has the same effect as PTCH2SRV_D in the old PID controller but without the spikes in servo demands. This gain helps to reduce rolling in turbulence. It should be increased in 0.01 increments as too high a value can lead to a high frequency pitch oscillation that could overstress the airframe.
|
||||
// @Range: 0 0.1
|
||||
// @Increment: 0.01
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_D", 2, AP_RollController, _kp_rate, 0.0),
|
||||
AP_GROUPINFO("K_D", 2, AP_RollController, _K_D, 0.0),
|
||||
|
||||
// @Param: K_I
|
||||
// @DisplayName: Roll integration gain
|
||||
// @Description: This is the gain for integration of the roll rate error. It has essentially the same effect as the I term in the old PID (RLL2SRV_I). This can be set to 0 as a default, however users can increment this to enable the controller trim out any roll trim offset.
|
||||
// @Range: 0 0.2
|
||||
// @Increment: 0.01
|
||||
// @DisplayName: Integrator Gain
|
||||
// @Description: This is the gain from the integral of bank angle to aileron. It has the same effect as PTCH2SRV_I in the old PID controller. Increasing this gain causes the controller to trim out steady offsets due to an out of trim aircraft.
|
||||
// @Range: 0 1.0
|
||||
// @Increment: 0.05
|
||||
// @User: User
|
||||
AP_GROUPINFO("K_I", 3, AP_RollController, _ki_rate, 0.0),
|
||||
AP_GROUPINFO("K_I", 3, AP_RollController, _K_I, 0.0),
|
||||
|
||||
// @Param: RMAX
|
||||
// @DisplayName: Roll max rate
|
||||
// @DisplayName: Maximum Roll Rate
|
||||
// @Description: This sets the maximum roll rate that the controller will demand (degrees/sec). Setting it to zero disables the limit. If this value is set too low, then the roll can't keep up with the navigation demands and the plane will start weaving. If it is set too high (or disabled by setting to zero) then ailerons will get large inputs at the start of turns. A limit of 60 degrees/sec is a good default.
|
||||
// @Range: 0 180
|
||||
// @Units: degrees/second
|
||||
// @Increment: 1
|
||||
// @User: User
|
||||
AP_GROUPINFO("RMAX", 4, AP_RollController, _max_rate, 60),
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RMAX", 4, AP_RollController, _max_rate, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
@ -77,6 +77,11 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
||||
}
|
||||
_last_t = tnow;
|
||||
|
||||
// Calculate equivalent gains so that values for K_P and K_I can be taken across from the old PID law
|
||||
// No conversion is required for K_D
|
||||
float kp_ff = max((_K_P - _K_I * _tau) * _tau - _K_D , 0);
|
||||
float ki_rate = _K_I * _tau;
|
||||
|
||||
if(_ahrs == NULL) return 0; // can't control without a reference
|
||||
float delta_time = (float)dt / 1000.0f;
|
||||
|
||||
@ -84,7 +89,7 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
||||
int32_t angle_err = angle - _ahrs->roll_sensor;
|
||||
|
||||
// Calculate the desired roll rate (deg/sec) from the angle error
|
||||
float desired_rate = angle_err * 0.01f * _kp_angle;
|
||||
float desired_rate = angle_err * 0.01f / _tau;
|
||||
|
||||
// Limit the demanded roll rate
|
||||
if (_max_rate && desired_rate < -_max_rate) desired_rate = -_max_rate;
|
||||
@ -104,9 +109,9 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
||||
// Don't integrate if in stabilise mode as the integrator will wind up against the pilots inputs
|
||||
if (!stabilize) {
|
||||
//only integrate if gain and time step are positive and airspeed above min value.
|
||||
if ((fabsf(_ki_rate) > 0) && (dt > 0) && (aspeed > float(aspd_min)))
|
||||
if ((ki_rate > 0) && (dt > 0) && (aspeed > float(aspd_min)))
|
||||
{
|
||||
float integrator_delta = rate_error * _ki_rate * scaler * delta_time;
|
||||
float integrator_delta = rate_error * ki_rate * scaler * delta_time;
|
||||
// prevent the integrator from increasing if surface defln demand is above the upper limit
|
||||
if (_last_out < -45) integrator_delta = max(integrator_delta , 0);
|
||||
// prevent the integrator from decreasing if surface defln demand is below the lower limit
|
||||
@ -121,7 +126,7 @@ int32_t AP_RollController::get_servo_out(int32_t angle, float scaler, bool stabi
|
||||
// Note the scaler is applied again. We want a 1/speed scaler applied to the feed-forward
|
||||
// path, but want a 1/speed^2 scaler applied to the rate error path.
|
||||
// This is because acceleration scales with speed^2, but rate scales with speed.
|
||||
_last_out = ( (rate_error * _kp_rate) + _integrator + (desired_rate * _kp_ff) ) * scaler;
|
||||
_last_out = ( (rate_error * _K_D) + _integrator + (desired_rate * kp_ff) ) * scaler;
|
||||
|
||||
// Convert to centi-degrees and constrain
|
||||
return constrain_float(_last_out * 100, -4500, 4500);
|
||||
|
@ -22,10 +22,10 @@ public:
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
AP_Float _kp_angle;
|
||||
AP_Float _kp_ff;
|
||||
AP_Float _kp_rate;
|
||||
AP_Float _ki_rate;
|
||||
AP_Float _tau;
|
||||
AP_Float _K_P;
|
||||
AP_Float _K_I;
|
||||
AP_Float _K_D;
|
||||
AP_Int16 _max_rate;
|
||||
uint32_t _last_t;
|
||||
float _last_out;
|
||||
|
@ -80,46 +80,43 @@ Initial assessment
|
||||
Roll control tuning
|
||||
-------------------
|
||||
|
||||
Basic Method 1:
|
||||
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
|
||||
This method is the simplest, but won't give the best result. For those
|
||||
users familiar with tuning the old PID controller gains, the K_P, K_I
|
||||
and K_D gains in this controller have the same effect, but there are some
|
||||
additional values that can be set by more advanced users.
|
||||
|
||||
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.
|
||||
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
|
||||
gain in increments of 0.1 until you are happy with the response.
|
||||
|
||||
2) If during 1) the wings start to 'waggle' and you are not happy with
|
||||
the speed of the response, then CTL_RLL_K_D can be increased in small
|
||||
increments of 0.01 until the wing waggle goes away and step 1 can be
|
||||
repeated. Do not go above 0.1 for CTL_RLL_K_D without checking the
|
||||
temperature of your servos when you land as in extreme cases turning
|
||||
up this gain can cause rapid servo movement and overheat the servos
|
||||
leading to premature failure.
|
||||
|
||||
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.
|
||||
Method 2:
|
||||
|
||||
Basic Method 2:
|
||||
|
||||
This method gives the best result, but requires more caution because
|
||||
This method can give a better 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 0.04 and CTL_RLL_K_P to 0.0
|
||||
1) Follow basic method 1) first
|
||||
|
||||
2) Increase CTL_RLL_K_D in increments of 0.01 until it it starts to
|
||||
oscillate, then halve it.
|
||||
2) Increase CTL_RLL_K_D in increments of 0.01 until it it starts to
|
||||
oscillate, then halve it.
|
||||
|
||||
3) Increase CTL_RLL_OMEGA from the default 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. If you go to far it will roll rapidly at first,
|
||||
but then have a noticeably delay to complete the last part of the
|
||||
roll, or you may get roll oscillation.
|
||||
|
||||
5) At this stage you may be able to increase CTL_RLL_OMEGA slightly
|
||||
for some more performance.
|
||||
3) Reduce CTL_RLL_TAU from the default value of 0.7 for a more rapid
|
||||
response if desired and if your aircraft is capable of doing so.
|
||||
If the bank angle starts to overshoot or you see wing 'waggle',
|
||||
you have gone too far.
|
||||
|
||||
Advanced:
|
||||
|
||||
@ -138,36 +135,38 @@ Advanced:
|
||||
increase the value for this gain.
|
||||
|
||||
3) If you can slow down the rate of roll and make the model bank more
|
||||
smoothly by reducing the roll rate limit CTL_RLL_RMAX
|
||||
parameter. The default is 60 degrees/sec which is fine for most
|
||||
models.
|
||||
smoothly by setting the roll rate limit CTL_RLL_RMAX parameter to a
|
||||
non zero value. A value of 60 deg/sec works weel for most models.
|
||||
The default is 0 which turns the rate limiter off and makes the
|
||||
effect of tuning easier to see.
|
||||
|
||||
4) If the model appears to roll rapidly initially and then appears to
|
||||
slow down and take noticeably longer to complete the roll, them
|
||||
this normally indicates that the parameter that sets the time
|
||||
constant of the roll maneuver CTL_RLL_OMEGA needs to be increased
|
||||
and CTL_RLL_K_P needs to be reduced.
|
||||
|
||||
Pitch Control Tuning
|
||||
--------------------
|
||||
|
||||
Basic Method 1:
|
||||
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
|
||||
This method is the simplest and but won't give the best result. For those
|
||||
users familiar with tuning the old PID controller gains, the K_P, K_I
|
||||
and K_D gains in this controller have the same effect, but there are some
|
||||
additional values that anbe set by more advanced users.
|
||||
|
||||
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.
|
||||
increase the CTL_PTCH_K_P parameter in increments of 0.1 you are happy
|
||||
with the speed of the response or it starts to porpoise a little. If
|
||||
you are happy with the response after this step, you can skip step 2)
|
||||
|
||||
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.
|
||||
2) If you get porposising and the response is still too sluggish, 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 until you have checked
|
||||
your servo temperatures immediately after landing as in extreme
|
||||
cases turning up this gain can cause rapid servo movement and overheat
|
||||
the servos leading to premature failure.
|
||||
|
||||
3) Now roll the model to maximum bank in each direction. The nose
|
||||
should stay fairly level during the turns without significant gain
|
||||
@ -180,51 +179,37 @@ old PID loops, but won't give the best result
|
||||
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
|
||||
change the CTL_PTCH_K_RLL parameter outside the range from 0.7 to
|
||||
1.4 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:
|
||||
Method 2:
|
||||
|
||||
This method gives the best result, but requires more caution because
|
||||
This method can give a better 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 0.04 and CTL_RLL_K_P to 0.0
|
||||
1) Follow Basic Method 1) first
|
||||
|
||||
2) Increase CTL_PTCH_K_D in increments of 0.01 until it it starts to
|
||||
oscillate, then halve it.
|
||||
|
||||
3) Increase CTL_PTCH_OMEGA from the default 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. If you go to far it will pitch rapidly at first,
|
||||
but then have a noticeably delay to complete the last part of the
|
||||
pitch, or you may get pitch oscillation.
|
||||
|
||||
5) At this stage you may be able to increase CTL_PTCH_OMEGA slightly
|
||||
for some more performance.
|
||||
2) Increase CTL_PTCH_K_D in increments of 0.01 until it it starts to
|
||||
oscillate, then halve it.
|
||||
|
||||
1) Reduce CTL_PTCH_TAU from the default value of 0.7 for a more rapid
|
||||
response if required and if your aircraft is capable of doing so.
|
||||
If the pitch response starts to overshoot, you have gone too far.
|
||||
|
||||
Advanced Options:
|
||||
|
||||
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.
|
||||
3) Increase CTL_PTCH_K_I from the default value to more rapidly trim
|
||||
out errors in pitch angle (you will need to monitor the nav_pitch
|
||||
and pitch in the tuning graphs window to do this).
|
||||
|
||||
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).
|
||||
2) 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 can be
|
||||
used to limit the amount of g produced during a pull-up or push
|
||||
down.
|
||||
|
||||
Yaw Control Tuning
|
||||
------------------
|
||||
|
Loading…
Reference in New Issue
Block a user