mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF : Reduce Z accel bias process noise to provide a more stable estimate
This commit is contained in:
parent
1f8b5a6d23
commit
db043744a4
@ -35,7 +35,7 @@
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00015f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
@ -56,7 +56,7 @@
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00015f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
@ -77,7 +77,7 @@
|
||||
#define GYRO_PNOISE_DEFAULT 0.015f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 1E-07f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00015f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.0001f
|
||||
#define MAGE_PNOISE_DEFAULT 0.0003f
|
||||
#define MAGB_PNOISE_DEFAULT 0.0003f
|
||||
#define VEL_GATE_DEFAULT 3
|
||||
|
Loading…
Reference in New Issue
Block a user