From fed542627428b7b7c049e97a1ab2135288547662 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 9 Mar 2012 09:03:47 +1100 Subject: [PATCH] DCM: after some experimentation, raise the ki values a bit this tracks the max gyro drift more accurately --- libraries/AP_DCM/AP_DCM.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DCM/AP_DCM.h b/libraries/AP_DCM/AP_DCM.h index d8a2d1f268..5ebe7f554f 100644 --- a/libraries/AP_DCM/AP_DCM.h +++ b/libraries/AP_DCM/AP_DCM.h @@ -41,8 +41,8 @@ public: // which will make us less prone to increasing omegaI // incorrectly due to sensor noise _gyro_drift_limit = imu->get_gyro_drift_rate(); - _ki_roll_pitch = _gyro_drift_limit * 3; - _ki_yaw = _gyro_drift_limit * 4; + _ki_roll_pitch = _gyro_drift_limit * 5; + _ki_yaw = _gyro_drift_limit * 8; } // Accessors