From 742c2b034f0aac080f99607cc9d1aa03baecaf50 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 26 Apr 2022 08:19:15 +0100 Subject: [PATCH] AC_AutoTune: allow high ANGLE_P gains --- libraries/AC_AutoTune/AC_AutoTune_Multi.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index 8b9f2982f4..3339d3fc4a 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -51,7 +51,7 @@ #define AUTOTUNE_RLPF_MAX 5.0f // maximum Rate Yaw filter value #define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value #define AUTOTUNE_RP_MAX 2.0f // maximum Rate P value -#define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value +#define AUTOTUNE_SP_MAX 40.0f // maximum Stab P value #define AUTOTUNE_SP_MIN 0.5f // maximum Stab P value #define AUTOTUNE_RP_ACCEL_MIN 4000.0f // Minimum acceleration for Roll and Pitch #define AUTOTUNE_Y_ACCEL_MIN 1000.0f // Minimum acceleration for Yaw