From cfe2507c0b0f2ae33e6b31d0287936050a12de27 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 9 Dec 2012 18:08:45 +0900 Subject: [PATCH] ArduCopter: reduce Rate Roll/Pitch P to 0.150 (was 0.175) and increase I to 0.1 (was 0.01) --- ArduCopter/config.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index b7acf013c2..ba650d394a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -724,10 +724,10 @@ # define MAX_INPUT_PITCH_ANGLE 4500 #endif #ifndef RATE_ROLL_P - # define RATE_ROLL_P 0.175 + # define RATE_ROLL_P 0.150 #endif #ifndef RATE_ROLL_I - # define RATE_ROLL_I 0.010 + # define RATE_ROLL_I 0.100 #endif #ifndef RATE_ROLL_D # define RATE_ROLL_D 0.004 @@ -737,10 +737,10 @@ #endif #ifndef RATE_PITCH_P - # define RATE_PITCH_P 0.175 + # define RATE_PITCH_P 0.150 #endif #ifndef RATE_PITCH_I - # define RATE_PITCH_I 0.010 + # define RATE_PITCH_I 0.100 #endif #ifndef RATE_PITCH_D # define RATE_PITCH_D 0.004