AP_NavEKF2: Faster learning of gyro scale factors

This commit is contained in:
Paul Riseborough 2015-10-23 11:47:54 +11:00 committed by Andrew Tridgell
parent a2f5962f77
commit 1eaf318b9b

View File

@ -34,7 +34,7 @@
#define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
// rover defaults
@ -57,7 +57,7 @@
#define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#else
// generic defaults (and for plane)
@ -80,7 +80,7 @@
#define FLOW_MEAS_DELAY 10
#define FLOW_NOISE_DEFAULT 0.25f
#define FLOW_GATE_DEFAULT 3
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
#define GSCALE_PNOISE_DEFAULT 3.0E-03f
#endif // APM_BUILD_DIRECTORY