From 3442c77f6199db9878b10631edceebde85add61b Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 20 Feb 2024 13:57:34 +1030 Subject: [PATCH] Copter: Autotune: Squash with small changes --- libraries/AC_AutoTune/AC_AutoTune_Multi.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index ca18a5a716aef..0c7371b23eab6 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -517,7 +517,7 @@ void AC_AutoTune_Multi::twitching_test_rate(float angle, float rate, float rate_ meas_angle_min = angle; } - // calculate early stopping time based on the time it takes to get to 75% + // calculate early stopping time based on the time it takes to get to 63.21% if (meas_rate_max < rate_target_max * 0.6321) { // the measurement not reached the 63.21% threshold yet step_time_limit_ms = (now - step_start_time_ms) * 3; @@ -600,7 +600,7 @@ void AC_AutoTune_Multi::twitching_test_angle(float angle, float rate, float angl meas_rate_min = rate; } - // calculate early stopping time based on the time it takes to get to 75% + // calculate early stopping time based on the time it takes to get to 63.21% if (meas_angle_max < angle_target_max * 0.6321) { // the measurement not reached the 63.21% threshold yet step_time_limit_ms = (now - step_start_time_ms) * 3;