AC_AutoTune: fix tracking of maximum angular acceleration

Issue introduced in https://github.com/ArduPilot/ardupilot/pull/27370
and partially fixed in https://github.com/ArduPilot/ardupilot/pull/27762,
though evidently not properly tested.

Failing to track the maximum can result in dangerously low values being
calculated for `ATC_ACCEL_[RPY]_MAX` and the vehicle becoming unflyable.

Make the variable a reference so that the maximum value is preserved
between function calls.
This commit is contained in:
Thomas Watson 2024-12-03 18:01:42 -06:00 committed by Randy Mackay
parent 9a5f81aa95
commit d7b26a2205
2 changed files with 2 additions and 2 deletions

View File

@ -644,7 +644,7 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl
} }
// twitching_measure_acceleration - measure rate of change of measurement // twitching_measure_acceleration - measure rate of change of measurement
void AC_AutoTune_Multi::twitching_measure_acceleration(float &accel_average, float rate, float rate_max) const void AC_AutoTune_Multi::twitching_measure_acceleration(float &accel_average, float rate, float &rate_max) const
{ {
if (rate_max < rate) { if (rate_max < rate) {
rate_max = rate; rate_max = rate;

View File

@ -156,7 +156,7 @@ private:
void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max); void twitching_test_angle(float angle, float rate, float angle_target, float &meas_angle_min, float &meas_angle_max, float &meas_rate_min, float &meas_rate_max);
// measure acceleration during twitch test // measure acceleration during twitch test
void twitching_measure_acceleration(float &accel_average, float rate, float rate_max) const; void twitching_measure_acceleration(float &accel_average, float rate, float &rate_max) const;
// updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back // updating_rate_d_up - increase D and adjust P to optimize the D term for a little bounce back
// optimize D term while keeping the maximum just below the target by adjusting P // optimize D term while keeping the maximum just below the target by adjusting P