From de1cfc8e340c54ede444b9ea0adf4fa7421fc4e5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 3 Mar 2012 20:47:15 +1100 Subject: [PATCH] Quaternion: drop the gyro drift rates down this should allow us to cope with noise more readily --- libraries/AP_Quaternion/AP_Quaternion.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Quaternion/AP_Quaternion.h b/libraries/AP_Quaternion/AP_Quaternion.h index 7d0f11d783..44ec9a238c 100644 --- a/libraries/AP_Quaternion/AP_Quaternion.h +++ b/libraries/AP_Quaternion/AP_Quaternion.h @@ -91,11 +91,11 @@ private: // true if we are doing centripetal acceleration correction bool _centripetal; - // maximum gyroscope measurement error in rad/s (set to 5 degrees/second) - static const float gyroMeasError = 5.0 * (M_PI/180.0); + // maximum gyroscope measurement error in rad/s (set to 2 degrees/second) + static const float gyroMeasError = 2.0 * (M_PI/180.0); - // maximum gyroscope drift rate in radians/s/s (set to 0.2 degrees/s/s) - static const float gyroMeasDrift = 0.2 * (PI/180.0); + // maximum gyroscope drift rate in radians/s/s (set to 0.03 degrees/s/s) + static const float gyroMeasDrift = 0.03 * (PI/180.0); float beta; float zeta;