mirror of https://github.com/ArduPilot/ardupilot
AC_Autotune: Fix bug introduced in #27370
This commit is contained in:
parent
14b505c3cb
commit
a4a9113cde
|
@ -1225,6 +1225,7 @@ void AC_AutoTune_Multi::twitch_test_init()
|
||||||
test_rate_min = 0.0;
|
test_rate_min = 0.0;
|
||||||
test_angle_max = 0.0;
|
test_angle_max = 0.0;
|
||||||
test_angle_min = 0.0;
|
test_angle_min = 0.0;
|
||||||
|
accel_measure_rate_max = 0.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
//run twitch test
|
//run twitch test
|
||||||
|
@ -1315,18 +1316,18 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
|
||||||
case RD_UP:
|
case RD_UP:
|
||||||
case RD_DOWN:
|
case RD_DOWN:
|
||||||
twitching_test_rate(lean_angle, rotation_rate, target_rate, test_rate_min, test_rate_max, test_angle_min);
|
twitching_test_rate(lean_angle, rotation_rate, target_rate, test_rate_min, test_rate_max, test_angle_min);
|
||||||
twitching_measure_acceleration(test_accel_max, rotation_rate, test_rate_max);
|
twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);
|
||||||
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
|
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
|
||||||
break;
|
break;
|
||||||
case RP_UP:
|
case RP_UP:
|
||||||
twitching_test_rate(lean_angle, rotation_rate, target_rate * (1 + 0.5 * aggressiveness), test_rate_min, test_rate_max, test_angle_min);
|
twitching_test_rate(lean_angle, rotation_rate, target_rate * (1 + 0.5 * aggressiveness), test_rate_min, test_rate_max, test_angle_min);
|
||||||
twitching_measure_acceleration(test_accel_max, rotation_rate, test_rate_max);
|
twitching_measure_acceleration(test_accel_max, rotation_rate, accel_measure_rate_max);
|
||||||
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
|
twitching_abort_rate(lean_angle, rotation_rate, angle_abort, test_rate_min, test_angle_min);
|
||||||
break;
|
break;
|
||||||
case SP_DOWN:
|
case SP_DOWN:
|
||||||
case SP_UP:
|
case SP_UP:
|
||||||
twitching_test_angle(lean_angle, rotation_rate, target_angle * (1 + 0.5 * aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);
|
twitching_test_angle(lean_angle, rotation_rate, target_angle * (1 + 0.5 * aggressiveness), test_angle_min, test_angle_max, test_rate_min, test_rate_max);
|
||||||
twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, test_rate_max);
|
twitching_measure_acceleration(test_accel_max, rotation_rate - dir_sign * start_rate, accel_measure_rate_max);
|
||||||
break;
|
break;
|
||||||
case RFF_UP:
|
case RFF_UP:
|
||||||
case MAX_GAINS:
|
case MAX_GAINS:
|
||||||
|
|
|
@ -193,6 +193,7 @@ private:
|
||||||
float test_rate_max; // the maximum angular rate achieved during TESTING_RATE
|
float test_rate_max; // the maximum angular rate achieved during TESTING_RATE
|
||||||
float test_angle_min; // the minimum angle achieved during TESTING_ANGLE
|
float test_angle_min; // the minimum angle achieved during TESTING_ANGLE
|
||||||
float test_angle_max; // the maximum angle achieved during TESTING_ANGLE
|
float test_angle_max; // the maximum angle achieved during TESTING_ANGLE
|
||||||
|
float accel_measure_rate_max; // the maximum rate used to measure average acceleration during twitch
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AC_AUTOTUNE_ENABLED
|
#endif // AC_AUTOTUNE_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue