From 4b47a618a4edaea617c837b46a0f868bdab20699 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 7 Sep 2014 22:14:40 +0900 Subject: [PATCH] Copter: reduce alt hold defaults Throttle Rate P to 5.0 (was 6.0) Throttle Accel P to 0.5 (was 0.75) Throttle Accel I to 1.0 (was 1.5) --- ArduCopter/config.h | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 77c2e41b3b..fdd22d92ec 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -685,7 +685,21 @@ // RATE control #ifndef THROTTLE_RATE_P - # define THROTTLE_RATE_P 6.0f + # define THROTTLE_RATE_P 5.0f +#endif + +// Throttle Accel control +#ifndef THROTTLE_ACCEL_P + # define THROTTLE_ACCEL_P 0.50f +#endif +#ifndef THROTTLE_ACCEL_I + # define THROTTLE_ACCEL_I 1.00f +#endif +#ifndef THROTTLE_ACCEL_D + # define THROTTLE_ACCEL_D 0.0f +#endif +#ifndef THROTTLE_ACCEL_IMAX + # define THROTTLE_ACCEL_IMAX 500 #endif // default maximum vertical velocity and acceleration the pilot may request @@ -705,20 +719,6 @@ # define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h #endif -// Throttle Accel control -#ifndef THROTTLE_ACCEL_P - # define THROTTLE_ACCEL_P 0.75f -#endif -#ifndef THROTTLE_ACCEL_I - # define THROTTLE_ACCEL_I 1.50f -#endif -#ifndef THROTTLE_ACCEL_D - # define THROTTLE_ACCEL_D 0.0f -#endif -#ifndef THROTTLE_ACCEL_IMAX - # define THROTTLE_ACCEL_IMAX 500 -#endif - ////////////////////////////////////////////////////////////////////////////// // Dataflash logging control //