From ccc659e8a9bb74064d5a3962918eb3023d5cee78 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 26 Aug 2012 10:45:45 +0900 Subject: [PATCH] ArduCopter: reduced Rate Roll and Pitch PID values RATE_ROLL_P, RATE_PITCH_P reduced to 0.165 (was 0.185) RATE_ROLL_D, RATE_PITCH_D reduced to 0.004 (was 0.008) --- ArduCopter/config.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 417bb8e4b9..eab360e7f9 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -698,26 +698,26 @@ // Stabilize Rate Control // #ifndef RATE_ROLL_P - # define RATE_ROLL_P 0.185 + # define RATE_ROLL_P 0.165 #endif #ifndef RATE_ROLL_I # define RATE_ROLL_I 0.0 #endif #ifndef RATE_ROLL_D - # define RATE_ROLL_D 0.008 + # define RATE_ROLL_D 0.004 #endif #ifndef RATE_ROLL_IMAX # define RATE_ROLL_IMAX 5.0 // degrees #endif #ifndef RATE_PITCH_P - # define RATE_PITCH_P 0.185 + # define RATE_PITCH_P 0.165 #endif #ifndef RATE_PITCH_I # define RATE_PITCH_I 0.0 #endif #ifndef RATE_PITCH_D - # define RATE_PITCH_D 0.008 + # define RATE_PITCH_D 0.004 #endif #ifndef RATE_PITCH_IMAX # define RATE_PITCH_IMAX 5.0 // degrees