From f892e0b00deb18cabf35008ce3291b4762296b9b Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 23 Dec 2011 14:24:03 -0800 Subject: [PATCH] increased crosstrack thanks to float math fix decreased loiter iterm, decreased throttle iterm based on simulator runs --- ArduCopter/config.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d99e0bfb4b..d06949b9f2 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -598,7 +598,7 @@ # define LOITER_P .3 // #endif #ifndef LOITER_I -# define LOITER_I 0.05 // +# define LOITER_I 0.01 // #endif #ifndef LOITER_IMAX # define LOITER_IMAX 30 // degreesĀ° @@ -630,7 +630,7 @@ # define THR_HOLD_P 0.4 // #endif #ifndef THR_HOLD_I -# define THR_HOLD_I 0.02 // with 4m error, 12.5s windup +# define THR_HOLD_I 0.01 // with 4m error, 12.5s windup #endif #ifndef THR_HOLD_IMAX # define THR_HOLD_IMAX 300 @@ -652,7 +652,7 @@ // Crosstrack compensation // #ifndef CROSSTRACK_GAIN -# define CROSSTRACK_GAIN 4 +# define CROSSTRACK_GAIN 40 #endif