Quaternion: minor tuning

This commit is contained in:
Andrew Tridgell 2012-03-07 18:31:35 +11:00
parent e470bf2354
commit ab1aec0f77
1 changed files with 2 additions and 2 deletions

View File

@ -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)