Browse Source

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
gps-1.3.1
Paul Riseborough 4 years ago committed by Andrew Tridgell
parent
commit
5eb7751682
  1. 8
      libraries/AP_NavEKF3/AP_NavEKF3.cpp

8
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -24,7 +24,7 @@ @@ -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 @@ @@ -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 @@ @@ -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 @@ @@ -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…
Cancel
Save