AP_NavEKF: update tuning defaults

Increase speed of scale factor learning
This commit is contained in:
Paul Riseborough 2016-05-21 22:10:32 +10:00 committed by Andrew Tridgell
parent 4c66e14563
commit da0622827d
1 changed files with 4 additions and 4 deletions

View File

@ -23,7 +23,7 @@
#define GYRO_P_NSE_DEFAULT 3.0E-02f #define GYRO_P_NSE_DEFAULT 3.0E-02f
#define ACC_P_NSE_DEFAULT 6.0E-01f #define ACC_P_NSE_DEFAULT 6.0E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-04f #define GBIAS_P_NSE_DEFAULT 1.0E-04f
#define GSCALE_P_NSE_DEFAULT 1.0E-05f #define GSCALE_P_NSE_DEFAULT 5.0E-04f
#define ABIAS_P_NSE_DEFAULT 1.0E-03f #define ABIAS_P_NSE_DEFAULT 1.0E-03f
#define MAG_P_NSE_DEFAULT 2.5E-02f #define MAG_P_NSE_DEFAULT 2.5E-02f
#define VEL_I_GATE_DEFAULT 500 #define VEL_I_GATE_DEFAULT 500
@ -47,7 +47,7 @@
#define GYRO_P_NSE_DEFAULT 3.0E-02f #define GYRO_P_NSE_DEFAULT 3.0E-02f
#define ACC_P_NSE_DEFAULT 6.0E-01f #define ACC_P_NSE_DEFAULT 6.0E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-04f #define GBIAS_P_NSE_DEFAULT 1.0E-04f
#define GSCALE_P_NSE_DEFAULT 1.0E-05f #define GSCALE_P_NSE_DEFAULT 5.0E-04f
#define ABIAS_P_NSE_DEFAULT 1.0E-03f #define ABIAS_P_NSE_DEFAULT 1.0E-03f
#define MAG_P_NSE_DEFAULT 2.5E-02f #define MAG_P_NSE_DEFAULT 2.5E-02f
#define VEL_I_GATE_DEFAULT 500 #define VEL_I_GATE_DEFAULT 500
@ -71,7 +71,7 @@
#define GYRO_P_NSE_DEFAULT 3.0E-02f #define GYRO_P_NSE_DEFAULT 3.0E-02f
#define ACC_P_NSE_DEFAULT 6.0E-01f #define ACC_P_NSE_DEFAULT 6.0E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-04f #define GBIAS_P_NSE_DEFAULT 1.0E-04f
#define GSCALE_P_NSE_DEFAULT 1.0E-05f #define GSCALE_P_NSE_DEFAULT 5.0E-04f
#define ABIAS_P_NSE_DEFAULT 1.0E-03f #define ABIAS_P_NSE_DEFAULT 1.0E-03f
#define MAG_P_NSE_DEFAULT 2.5E-02f #define MAG_P_NSE_DEFAULT 2.5E-02f
#define VEL_I_GATE_DEFAULT 500 #define VEL_I_GATE_DEFAULT 500
@ -95,7 +95,7 @@
#define GYRO_P_NSE_DEFAULT 3.0E-02f #define GYRO_P_NSE_DEFAULT 3.0E-02f
#define ACC_P_NSE_DEFAULT 6.0E-01f #define ACC_P_NSE_DEFAULT 6.0E-01f
#define GBIAS_P_NSE_DEFAULT 1.0E-04f #define GBIAS_P_NSE_DEFAULT 1.0E-04f
#define GSCALE_P_NSE_DEFAULT 1.0E-05f #define GSCALE_P_NSE_DEFAULT 5.0E-04f
#define ABIAS_P_NSE_DEFAULT 1.0E-03f #define ABIAS_P_NSE_DEFAULT 1.0E-03f
#define MAG_P_NSE_DEFAULT 2.5E-02f #define MAG_P_NSE_DEFAULT 2.5E-02f
#define VEL_I_GATE_DEFAULT 500 #define VEL_I_GATE_DEFAULT 500