From 4032ac988440b5918fde8dd97fa78c371a1ac322 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 1 Feb 2021 10:07:12 +0900 Subject: [PATCH] AC_AutoTune: level criteria is 5deg for plane and 2.5 for all others --- libraries/AC_AutoTune/AC_AutoTune.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index cc76ad28c3..9762e15576 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -43,8 +43,13 @@ #define AUTOTUNE_PILOT_OVERRIDE_TIMEOUT_MS 500 // restart tuning if pilot has left sticks in middle for 2 seconds #define AUTOTUNE_TESTING_STEP_TIMEOUT_MS 1000U // timeout for tuning mode's testing step -#define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level -#define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch +#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) + # define AUTOTUNE_LEVEL_ANGLE_CD 500 // angle which qualifies as level (Plane uses more relaxed 5deg) + # define AUTOTUNE_LEVEL_RATE_RP_CD 1000 // rate which qualifies as level for roll and pitch (Plane uses more relaxed 10deg/sec) +#else + # define AUTOTUNE_LEVEL_ANGLE_CD 250 // angle which qualifies as level + # define AUTOTUNE_LEVEL_RATE_RP_CD 500 // rate which qualifies as level for roll and pitch +#endif #define AUTOTUNE_LEVEL_RATE_Y_CD 750 // rate which qualifies as level for yaw #define AUTOTUNE_REQUIRED_LEVEL_TIME_MS 500 // time we require the aircraft to be level #define AUTOTUNE_LEVEL_TIMEOUT_MS 2000 // time out for level