Skip to content

Commit 3bf8b41

Browse files
committed
AC_AutoTune: Limit Angle P for plane to 10
1 parent f8f9533 commit 3bf8b41

File tree

1 file changed

+7
-1
lines changed

1 file changed

+7
-1
lines changed

libraries/AC_AutoTune/AC_AutoTune_Multi.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,13 @@
5858
#define AUTOTUNE_FLTE_MIN 2.5 // minimum Rate Yaw error filter value
5959
#define AUTOTUNE_RP_MIN 0.01 // minimum Rate P value
6060
#define AUTOTUNE_RP_MAX 2.0 // maximum Rate P value
61-
#define AUTOTUNE_SP_MAX 40.0 // maximum Stab P value
61+
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+
6268
#define AUTOTUNE_SP_MIN 0.5 // maximum Stab P value
6369
#define AUTOTUNE_RP_ACCEL_MIN 4000.0 // Minimum acceleration for Roll and Pitch
6470
#define AUTOTUNE_Y_ACCEL_MIN 1000.0 // Minimum acceleration for Yaw

0 commit comments

Comments
 (0)