From 1c57c6a266d0ae6e6d1bcabd40f12ce4cb2f6408 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 9 Mar 2015 17:44:51 +0900 Subject: [PATCH] Copter: Autotune update yaw filt and rate P max --- ArduCopter/control_autotune.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_autotune.pde b/ArduCopter/control_autotune.pde index 8c7e6ba633..66e004086d 100644 --- a/ArduCopter/control_autotune.pde +++ b/ArduCopter/control_autotune.pde @@ -60,9 +60,9 @@ #define AUTOTUNE_RD_MIN 0.002f // minimum Rate D value #define AUTOTUNE_RD_MAX 0.050f // maximum Rate D value #define AUTOTUNE_RLPF_MIN 0.1f // minimum Rate D value -#define AUTOTUNE_RLPF_MAX 20.0f // maximum Rate D value +#define AUTOTUNE_RLPF_MAX 10.0f // maximum Rate D value #define AUTOTUNE_RP_MIN 0.01f // minimum Rate P value -#define AUTOTUNE_RP_MAX 100.0f // maximum Rate P value +#define AUTOTUNE_RP_MAX 5.0f // maximum Rate P value #define AUTOTUNE_SP_MAX 20.0f // maximum Stab P value #define AUTOTUNE_SP_MIN 1.0f // maximum Stab P value #define AUTOTUNE_ACCEL_RP_BACKOFF 1.5f // back off from maximum acceleration