Skip to content

Commit

Permalink
Copter: Autotune: Squash with Fails
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Feb 20, 2024
1 parent ac0f08e commit c9bbd67
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -929,13 +929,16 @@ 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;
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Max Rate P Gain Determination Failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Rate P Gain Determination Failed");
mode = FAILED;
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
}
Expand Down Expand Up @@ -984,7 +987,7 @@ 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: Max Angle P Gain Determination Failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "AutoTune: Angle P Gain Determination Failed");
mode = FAILED;
LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED);
}
Expand Down

0 comments on commit c9bbd67

Please sign in to comment.