We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent f8f9533 commit 3bf8b41Copy full SHA for 3bf8b41
libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
@@ -58,7 +58,13 @@
58
#define AUTOTUNE_FLTE_MIN 2.5 // minimum Rate Yaw error filter value
59
#define AUTOTUNE_RP_MIN 0.01 // minimum Rate P value
60
#define AUTOTUNE_RP_MAX 2.0 // maximum Rate P value
61
-#define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value
+
62
+#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
63
+ #define AUTOTUNE_SP_MAX 10.0 // maximum Stab P value
64
+#else
65
+ #define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value
66
+#endif
67
68
#define AUTOTUNE_SP_MIN 0.5 // maximum Stab P value
69
#define AUTOTUNE_RP_ACCEL_MIN 4000.0 // Minimum acceleration for Roll and Pitch
70
#define AUTOTUNE_Y_ACCEL_MIN 1000.0 // Minimum acceleration for Yaw
0 commit comments