From 6748ffd1124c8fc0c591835382706c1e9cb33035 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Fri, 5 Aug 2011 16:21:21 +0000 Subject: [PATCH] 2.0.39 added defines for CH7 behavior, Tweaked Loiter config based on testing by Jack. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3021 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/config.h | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index 1525fb17f8..e8ad874db1 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -58,6 +58,14 @@ # define SONAR_TYPE MAX_SONAR_XL #endif +////////////////////////////////////////////////////////////////////////////// +// Acrobatics +// + +#ifndef CH7_OPTION +# define CH7_OPTION DO_SET_HOVER +#endif + ////////////////////////////////////////////////////////////////////////////// // AIRSPEED_SENSOR @@ -378,16 +386,16 @@ // Navigation control gains // #ifndef NAV_LOITER_P -# define NAV_LOITER_P 1.4 // +# define NAV_LOITER_P 2.4 //1.4 // #endif #ifndef NAV_LOITER_I -# define NAV_LOITER_I 0.015 // +# define NAV_LOITER_I 0.01 // #endif #ifndef NAV_LOITER_D -# define NAV_LOITER_D 1.4 // +# define NAV_LOITER_D 1.0 //1.4 // #endif #ifndef NAV_LOITER_IMAX -# define NAV_LOITER_IMAX 12 // degreesĀ° +# define NAV_LOITER_IMAX 12 // degreesĀ° #endif @@ -420,7 +428,7 @@ # define THROTTLE_I 0.01 //with 4m error, 12.5s windup #endif #ifndef THROTTLE_D -# define THROTTLE_D 0.4 // upped with filter +# define THROTTLE_D 0.4 // upped with filter #endif #ifndef THROTTLE_IMAX # define THROTTLE_IMAX 30