mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_NavEKF2: Tuning changes to make attitude less sensitive to GPS and compass errors
This commit is contained in:
parent
3549c717db
commit
0562529729
@ -19,12 +19,12 @@
|
||||
#define POSNE_NOISE_DEFAULT 1.0f
|
||||
#define ALT_NOISE_DEFAULT 5.0f
|
||||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define GYRO_PNOISE_DEFAULT 0.001f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.5E-02f
|
||||
#define VEL_GATE_DEFAULT 3
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
#define POS_GATE_DEFAULT 3
|
||||
#define HGT_GATE_DEFAULT 3
|
||||
#define MAG_GATE_DEFAULT 3
|
||||
@ -43,12 +43,12 @@
|
||||
#define POSNE_NOISE_DEFAULT 1.0f
|
||||
#define ALT_NOISE_DEFAULT 2.0f
|
||||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define GYRO_PNOISE_DEFAULT 0.001f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.5E-02f
|
||||
#define VEL_GATE_DEFAULT 3
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
#define POS_GATE_DEFAULT 3
|
||||
#define HGT_GATE_DEFAULT 3
|
||||
#define MAG_GATE_DEFAULT 3
|
||||
@ -67,15 +67,15 @@
|
||||
#define POSNE_NOISE_DEFAULT 1.0f
|
||||
#define ALT_NOISE_DEFAULT 5.0f
|
||||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define GYRO_PNOISE_DEFAULT 0.001f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.5E-02f
|
||||
#define VEL_GATE_DEFAULT 5
|
||||
#define POS_GATE_DEFAULT 5
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
#define POS_GATE_DEFAULT 3
|
||||
#define HGT_GATE_DEFAULT 4
|
||||
#define MAG_GATE_DEFAULT 3
|
||||
#define MAG_GATE_DEFAULT 2
|
||||
#define MAG_CAL_DEFAULT 0
|
||||
#define GLITCH_RADIUS_DEFAULT 25
|
||||
#define FLOW_MEAS_DELAY 10
|
||||
@ -91,12 +91,12 @@
|
||||
#define POSNE_NOISE_DEFAULT 1.0f
|
||||
#define ALT_NOISE_DEFAULT 5.0f
|
||||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define GYRO_PNOISE_DEFAULT 0.001f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.5E-02f
|
||||
#define VEL_GATE_DEFAULT 3
|
||||
#define VEL_GATE_DEFAULT 2
|
||||
#define POS_GATE_DEFAULT 3
|
||||
#define HGT_GATE_DEFAULT 3
|
||||
#define MAG_GATE_DEFAULT 3
|
||||
|
Loading…
Reference in New Issue
Block a user