mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Retune IMU process noise
Required to achieve equivalent fusion noise and weighting on IMU vs other sources to previous param defaults with the old covariance prediction equations.
This commit is contained in:
parent
8db073a8d6
commit
a24df9d633
|
@ -22,10 +22,10 @@
|
|||
#define POSNE_M_NSE_DEFAULT 0.5f
|
||||
#define ALT_M_NSE_DEFAULT 2.0f
|
||||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#define GYRO_P_NSE_DEFAULT 1.5E-02f
|
||||
#define ACC_P_NSE_DEFAULT 3.5E-01f
|
||||
#define GYRO_P_NSE_DEFAULT 1.0E-02f
|
||||
#define ACC_P_NSE_DEFAULT 2.5E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -48,10 +48,10 @@
|
|||
#define POSNE_M_NSE_DEFAULT 0.5f
|
||||
#define ALT_M_NSE_DEFAULT 2.0f
|
||||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#define GYRO_P_NSE_DEFAULT 1.5E-02f
|
||||
#define ACC_P_NSE_DEFAULT 3.5E-01f
|
||||
#define GYRO_P_NSE_DEFAULT 1.0E-02f
|
||||
#define ACC_P_NSE_DEFAULT 2.5E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -74,10 +74,10 @@
|
|||
#define POSNE_M_NSE_DEFAULT 0.5f
|
||||
#define ALT_M_NSE_DEFAULT 3.0f
|
||||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#define GYRO_P_NSE_DEFAULT 1.5E-02f
|
||||
#define ACC_P_NSE_DEFAULT 3.5E-01f
|
||||
#define GYRO_P_NSE_DEFAULT 1.0E-02f
|
||||
#define ACC_P_NSE_DEFAULT 2.5E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -100,10 +100,10 @@
|
|||
#define POSNE_M_NSE_DEFAULT 0.5f
|
||||
#define ALT_M_NSE_DEFAULT 2.0f
|
||||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#define GYRO_P_NSE_DEFAULT 1.5E-02f
|
||||
#define ACC_P_NSE_DEFAULT 3.5E-01f
|
||||
#define GYRO_P_NSE_DEFAULT 1.0E-02f
|
||||
#define ACC_P_NSE_DEFAULT 2.5E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 3.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
|
Loading…
Reference in New Issue