From 03933df5b7a0addb40567f2a5eb483762a9657b1 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Thu, 11 Oct 2012 17:25:01 +0900 Subject: [PATCH] ArduCopter: set default rate roll and pitch I terms to 0.010, and rate yaw to 0.015 Updated after discussing with Marco --- ArduCopter/config.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index fd45cc7554..f3508ed4d1 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -699,7 +699,7 @@ # define RATE_ROLL_P 0.175 #endif #ifndef RATE_ROLL_I - # define RATE_ROLL_I 0.02 + # define RATE_ROLL_I 0.010 #endif #ifndef RATE_ROLL_D # define RATE_ROLL_D 0.004 @@ -712,7 +712,7 @@ # define RATE_PITCH_P 0.175 #endif #ifndef RATE_PITCH_I - # define RATE_PITCH_I 0.02 + # define RATE_PITCH_I 0.010 #endif #ifndef RATE_PITCH_D # define RATE_PITCH_D 0.004 @@ -725,7 +725,7 @@ # define RATE_YAW_P .25 #endif #ifndef RATE_YAW_I - # define RATE_YAW_I 0.02 + # define RATE_YAW_I 0.015 #endif #ifndef RATE_YAW_D # define RATE_YAW_D 0.000