mirror of https://github.com/ArduPilot/ardupilot
Quaternion: bumb up gyro drift limit to match DCM
This commit is contained in:
parent
a874f920d5
commit
e2b2c9181e
|
@ -103,7 +103,7 @@ private:
|
||||||
|
|
||||||
// maximum gyroscope drift rate in radians/s/s (set to 0.005
|
// maximum gyroscope drift rate in radians/s/s (set to 0.005
|
||||||
// degrees/s/s, which is 0.3 degrees/s/minute)
|
// degrees/s/s, which is 0.3 degrees/s/minute)
|
||||||
static const float gyroMeasDrift = 0.005 * (PI/180.0);
|
static const float gyroMeasDrift = 0.04 * (PI/180.0);
|
||||||
|
|
||||||
float beta;
|
float beta;
|
||||||
float zeta;
|
float zeta;
|
||||||
|
|
Loading…
Reference in New Issue