From 95ac9d163e6bf0d7558aa288804d5e55ea32b1ed Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 14 Jan 2012 10:55:06 -0800 Subject: [PATCH] lowered Loiter I, commented out unused var --- ArduCopter/Attitude.pde | 2 +- ArduCopter/config.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index c99cdb0259..9515f60189 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -166,7 +166,7 @@ static int16_t get_nav_throttle(int32_t z_error) { static int16_t old_output = 0; - static int16_t rate_d = 0; + //static int16_t rate_d = 0; int16_t rate_error; int16_t output; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index c9276f957a..c662b0baa0 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -614,7 +614,7 @@ # define LOITER_P 2.0 // was .25 in previous #endif #ifndef LOITER_I -# define LOITER_I 0.05 // Wind control +# define LOITER_I 0.04 // Wind control #endif #ifndef LOITER_IMAX # define LOITER_IMAX 30 // degreesĀ°