mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF: reduced On Ground yaw gyro bias drift variance scaler
This commit is contained in:
parent
619fffec3e
commit
fec4fd463c
@ -30,7 +30,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
|
||||
fusionModeGPS(0), // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs, no velocity, 3 = Force postion and velocity measurements to zero (only used during pre-arm or ground testing)
|
||||
covTimeStepMax(0.07f), // maximum time (sec) between covariance prediction updates
|
||||
covDelAngMax(0.05f), // maximum delta angle between covariance prediction updates
|
||||
yawVarScale(2.0f), // scale factor applied to yaw gyro errors when on ground
|
||||
yawVarScale(1.0f), // scale factor applied to yaw gyro errors when on ground
|
||||
TASmsecMax(333), // maximum allowed interal between airspeed measurement updates
|
||||
MAGmsecMax(333), // maximum allowed interval between magnetometer measurement updates
|
||||
HGTmsecMax(1000), // maximum interval between height measurement updates
|
||||
|
Loading…
Reference in New Issue
Block a user