mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: Autotune: Fail when bad tune is expected
This commit is contained in:
parent
13fb69be7c
commit
54618dd903
@ -932,13 +932,18 @@ void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_mi
|
||||
if (tune_d <= tune_d_min) {
|
||||
tune_d = tune_d_min;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Rate D Gain Determination Failed");
|
||||
mode = FAILED;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
|
||||
}
|
||||
// decrease P gain to match D gain reduction
|
||||
tune_p -= tune_p*tune_p_step_ratio;
|
||||
// do not decrease the P term past the minimum
|
||||
if (tune_p <= tune_p_min) {
|
||||
tune_p = tune_p_min;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Rate P Gain Determination Failed");
|
||||
mode = FAILED;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
|
||||
}
|
||||
// cancel change in direction
|
||||
positive_direction = !positive_direction;
|
||||
@ -987,6 +992,9 @@ void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, f
|
||||
tune_p = tune_p_min;
|
||||
counter = AUTOTUNE_SUCCESS_COUNT;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Angle P Gain Determination Failed");
|
||||
mode = FAILED;
|
||||
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user