mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: check for high ratio of rmsD to rmsP in tuning
This commit is contained in:
parent
e070aeebe3
commit
021aebeac0
@ -277,21 +277,45 @@ float AP_Tuning_Plane::controller_error(uint8_t parm)
|
||||
if (!plane.quadplane.available()) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// in general a good tune will have rmsP significantly greater
|
||||
// than rmsD. Otherwise it is too easy to push D too high while
|
||||
// tuning a quadplane and end up with D dominating
|
||||
const float max_P_D_ratio = 3.0f;
|
||||
|
||||
switch(parm) {
|
||||
// special handling of dual-parameters
|
||||
case TUNING_RATE_ROLL_PI:
|
||||
case TUNING_RATE_ROLL_P:
|
||||
case TUNING_RATE_ROLL_I:
|
||||
case TUNING_RATE_ROLL_D:
|
||||
return plane.quadplane.attitude_control->control_monitor_rms_output_roll();
|
||||
|
||||
case TUNING_RATE_ROLL_D: {
|
||||
// special case for D term to keep it well below P
|
||||
float rms_P = plane.quadplane.attitude_control->control_monitor_rms_output_roll_P();
|
||||
float rms_D = plane.quadplane.attitude_control->control_monitor_rms_output_roll_D();
|
||||
if (rms_P < rms_D * max_P_D_ratio) {
|
||||
return max_P_D_ratio;
|
||||
}
|
||||
return rms_P+rms_D;
|
||||
}
|
||||
|
||||
|
||||
case TUNING_RATE_PITCH_PI:
|
||||
case TUNING_RATE_PITCH_P:
|
||||
case TUNING_RATE_PITCH_I:
|
||||
case TUNING_RATE_PITCH_D:
|
||||
return plane.quadplane.attitude_control->control_monitor_rms_output_pitch();
|
||||
|
||||
case TUNING_RATE_PITCH_D: {
|
||||
// special case for D term to keep it well below P
|
||||
float rms_P = plane.quadplane.attitude_control->control_monitor_rms_output_pitch_P();
|
||||
float rms_D = plane.quadplane.attitude_control->control_monitor_rms_output_pitch_D();
|
||||
if (rms_P < rms_D * max_P_D_ratio) {
|
||||
return max_P_D_ratio;
|
||||
}
|
||||
return rms_P+rms_D;
|
||||
}
|
||||
|
||||
case TUNING_RATE_YAW_PI:
|
||||
case TUNING_RATE_YAW_P:
|
||||
case TUNING_RATE_YAW_I:
|
||||
|
Loading…
Reference in New Issue
Block a user