AP_NavEKF3: Increase default value of EK3_ABIAS_P_NSE

This is required because some hardware setups with RTK GPS have experienced a collapse of the delta velocity state variances.
This commit is contained in:
Paul Riseborough 2023-05-16 19:46:29 +10:00 committed by Randy Mackay
parent 69b26836f0
commit 04d21fc368
1 changed files with 4 additions and 4 deletions

View File

@ -25,7 +25,7 @@
#define GYRO_P_NSE_DEFAULT 1.5E-02f
#define ACC_P_NSE_DEFAULT 3.5E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-03f
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
#define ABIAS_P_NSE_DEFAULT 6.0E-03f
#define MAGB_P_NSE_DEFAULT 1.0E-04f
#define MAGE_P_NSE_DEFAULT 1.0E-03f
#define VEL_I_GATE_DEFAULT 500
@ -51,7 +51,7 @@
#define GYRO_P_NSE_DEFAULT 1.5E-02f
#define ACC_P_NSE_DEFAULT 3.5E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-03f
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
#define ABIAS_P_NSE_DEFAULT 6.0E-03f
#define MAGB_P_NSE_DEFAULT 1.0E-04f
#define MAGE_P_NSE_DEFAULT 1.0E-03f
#define VEL_I_GATE_DEFAULT 500
@ -77,7 +77,7 @@
#define GYRO_P_NSE_DEFAULT 1.5E-02f
#define ACC_P_NSE_DEFAULT 3.5E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-03f
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
#define ABIAS_P_NSE_DEFAULT 6.0E-03f
#define MAGB_P_NSE_DEFAULT 1.0E-04f
#define MAGE_P_NSE_DEFAULT 1.0E-03f
#define VEL_I_GATE_DEFAULT 500
@ -103,7 +103,7 @@
#define GYRO_P_NSE_DEFAULT 1.5E-02f
#define ACC_P_NSE_DEFAULT 3.5E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-03f
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
#define ABIAS_P_NSE_DEFAULT 6.0E-03f
#define MAGB_P_NSE_DEFAULT 1.0E-04f
#define MAGE_P_NSE_DEFAULT 1.0E-03f
#define VEL_I_GATE_DEFAULT 500