From 93c4b75a604cbf311616a8ade3dd632e0c880888 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 19 Jan 2024 12:50:35 +1100 Subject: [PATCH] APM_Control: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG --- libraries/APM_Control/AP_AutoTune.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index d93dbb0d3a..829ff10a38 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -211,7 +211,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) att_limit_deg = aparm.roll_limit_cd * 0.01; break; case AUTOTUNE_PITCH: - att_limit_deg = MIN(abs(aparm.pitch_limit_max_cd),abs(aparm.pitch_limit_min_cd))*0.01; + att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01; break; case AUTOTUNE_YAW: // arbitrary value for yaw angle