From 801a442ffb9ea8b91a2c2f1f9758c603d5072bc5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 7 Mar 2012 18:31:35 +1100 Subject: [PATCH] Quaternion: minor tuning --- libraries/AP_Quaternion/AP_Quaternion.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Quaternion/AP_Quaternion.h b/libraries/AP_Quaternion/AP_Quaternion.h index 9f115eeafe..861e3164b7 100644 --- a/libraries/AP_Quaternion/AP_Quaternion.h +++ b/libraries/AP_Quaternion/AP_Quaternion.h @@ -98,8 +98,8 @@ private: // true if we are doing centripetal acceleration correction bool _centripetal; - // maximum gyroscope measurement error in rad/s (set to 40 degrees/second) - static const float gyroMeasError = 10.0 * (M_PI/180.0); + // maximum gyroscope measurement error in rad/s (set to 7 degrees/second) + static const float gyroMeasError = 7.0 * (M_PI/180.0); // maximum gyroscope drift rate in radians/s/s (set to 0.005 // degrees/s/s, which is 0.3 degrees/s/minute)