mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Adjust gyro bias process noise tuning
NEw value is a compromise between roll/pitch angle and horizontal state velocity estimation errors and the noise in the gyro bias estimate
This commit is contained in:
parent
ed30a7ce35
commit
82ed96a927
|
@ -24,7 +24,7 @@
|
|||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#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 GBIAS_P_NSE_DEFAULT 3.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
|
@ -50,7 +50,7 @@
|
|||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#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 GBIAS_P_NSE_DEFAULT 3.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
|
@ -76,7 +76,7 @@
|
|||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#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 GBIAS_P_NSE_DEFAULT 3.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
|
@ -102,7 +102,7 @@
|
|||
#define MAG_M_NSE_DEFAULT 0.05f
|
||||
#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 GBIAS_P_NSE_DEFAULT 3.0E-04f
|
||||
#define ABIAS_P_NSE_DEFAULT 1.0E-03f
|
||||
#define MAGB_P_NSE_DEFAULT 1.0E-04f
|
||||
#define MAGE_P_NSE_DEFAULT 1.0E-03f
|
||||
|
|
Loading…
Reference in New Issue