mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Increase gyro bias process noise
This is required to stop the bias estimate from becoming too static towards the end of longer flights.
This commit is contained in:
parent
481a55867e
commit
d150904dc6
|
@ -34,7 +34,7 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
|
@ -55,7 +55,7 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
|
@ -76,7 +76,7 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
|
|
Loading…
Reference in New Issue