AC_AutoTune: fix gain determination fail logic

This commit is contained in:
Bill Geyer 2022-04-13 23:41:58 -04:00 committed by Andrew Tridgell
parent aaa64a067a
commit 6e3f1918c2
1 changed files with 2 additions and 3 deletions

View File

@ -211,8 +211,7 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign)
{ {
// if tune complete or beyond frequency range or no max allowed gains then exit testing // if tune complete or beyond frequency range or no max allowed gains then exit testing
if (tune_type == TUNE_COMPLETE || if (tune_type == TUNE_COMPLETE ||
(tune_type == RP_UP && max_rate_p.max_allowed <= 0.0f) || ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) ||
(tune_type == RD_UP && max_rate_d.max_allowed <= 0.0f) ||
((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq))){ ((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq))){
load_gains(GAIN_ORIGINAL); load_gains(GAIN_ORIGINAL);
@ -224,7 +223,7 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign)
// hold level attitude // hold level attitude
attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true); attitude_control->input_euler_angle_roll_pitch_yaw(roll_cd, pitch_cd, desired_yaw_cd, true);
if ((tune_type == RP_UP && max_rate_p.max_allowed <= 0.0f) || (tune_type == RD_UP && max_rate_d.max_allowed <= 0.0f)) { if ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) {
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed"); gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed");
mode = FAILED; mode = FAILED;
AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED); AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED);