From e9702efada56efa2df5288f9126449ba3230c9c1 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sat, 16 Apr 2011 20:42:59 +0000 Subject: [PATCH] lowered Pitch max for nav git-svn-id: https://arducopter.googlecode.com/svn/trunk@1894 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/config.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index c187ff0003..8607700301 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -285,7 +285,7 @@ #endif #ifndef ACRO_RATE_YAW_P -# define ACRO_RATE_YAW_P .1 // used to control response in turning +# define ACRO_RATE_YAW_P .13 // used to control response in turning #endif #ifndef ACRO_RATE_YAW_I # define ACRO_RATE_YAW_I 0.0 @@ -353,7 +353,7 @@ // // how much to we pitch towards the target #ifndef PITCH_MAX -# define PITCH_MAX 25 // degrees +# define PITCH_MAX 15 // degrees #endif @@ -370,7 +370,7 @@ # define NAV_D 0.00 // should always be 0 #endif #ifndef NAV_IMAX -# define NAV_IMAX 250 // 250 degrees +# define NAV_IMAX 250 // 250 Lat and Longtitude #endif