mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Allow for faster accel bias change in-flight
Fixes a problem observed in a flight log where rapid temperature change caused the accel bias to change faster than the EKF could keep up. This allows the bias to be learned faster but with acceptable level of noise in the estimate
This commit is contained in:
parent
191c34612d
commit
fa435d0323
|
@ -24,7 +24,7 @@
|
|||
#define ACC_P_NSE_DEFAULT 6.0E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define GSCALE_P_NSE_DEFAULT 5.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 5.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 5.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 5.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -49,7 +49,7 @@
|
|||
#define ACC_P_NSE_DEFAULT 6.0E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define GSCALE_P_NSE_DEFAULT 5.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 5.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 5.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 5.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -74,7 +74,7 @@
|
|||
#define ACC_P_NSE_DEFAULT 6.0E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define GSCALE_P_NSE_DEFAULT 5.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 5.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 5.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 5.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
@ -99,7 +99,7 @@
|
|||
#define ACC_P_NSE_DEFAULT 6.0E-01f
|
||||
#define GBIAS_P_NSE_DEFAULT 1.0E-04f
|
||||
#define GSCALE_P_NSE_DEFAULT 5.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define ABIAS_P_NSE_DEFAULT 5.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 5.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 5.0E-03f
|
||||
#define VEL_I_GATE_DEFAULT 500
|
||||
|
|
Loading…
Reference in New Issue