mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Update default parameters
Updates from preliminary tuning in Replay
This commit is contained in:
parent
73686dfa89
commit
53e58f1075
|
@ -22,9 +22,9 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.0E-03f
|
||||
#define VEL_GATE_DEFAULT 5
|
||||
#define POS_GATE_DEFAULT 5
|
||||
#define HGT_GATE_DEFAULT 5
|
||||
|
@ -34,7 +34,7 @@
|
|||
#define FLOW_MEAS_DELAY 10
|
||||
#define FLOW_NOISE_DEFAULT 0.25f
|
||||
#define FLOW_GATE_DEFAULT 3
|
||||
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
|
||||
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
||||
// rover defaults
|
||||
|
@ -45,9 +45,9 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.0E-03f
|
||||
#define VEL_GATE_DEFAULT 5
|
||||
#define POS_GATE_DEFAULT 5
|
||||
#define HGT_GATE_DEFAULT 5
|
||||
|
@ -57,7 +57,7 @@
|
|||
#define FLOW_MEAS_DELAY 10
|
||||
#define FLOW_NOISE_DEFAULT 0.25f
|
||||
#define FLOW_GATE_DEFAULT 3
|
||||
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
|
||||
|
||||
#else
|
||||
// generic defaults (and for plane)
|
||||
|
@ -68,19 +68,19 @@
|
|||
#define MAG_NOISE_DEFAULT 0.05f
|
||||
#define GYRO_PNOISE_DEFAULT 0.005f
|
||||
#define ACC_PNOISE_DEFAULT 0.25f
|
||||
#define GBIAS_PNOISE_DEFAULT 5E-06f
|
||||
#define ABIAS_PNOISE_DEFAULT 0.00005f
|
||||
#define MAG_PNOISE_DEFAULT 0.0003f
|
||||
#define GBIAS_PNOISE_DEFAULT 7.0E-05f
|
||||
#define ABIAS_PNOISE_DEFAULT 1.0E-04f
|
||||
#define MAG_PNOISE_DEFAULT 2.0E-03f
|
||||
#define VEL_GATE_DEFAULT 5
|
||||
#define POS_GATE_DEFAULT 5
|
||||
#define HGT_GATE_DEFAULT 5
|
||||
#define HGT_GATE_DEFAULT 10
|
||||
#define MAG_GATE_DEFAULT 3
|
||||
#define MAG_CAL_DEFAULT 3
|
||||
#define GLITCH_RADIUS_DEFAULT 25
|
||||
#define FLOW_MEAS_DELAY 10
|
||||
#define FLOW_NOISE_DEFAULT 0.25f
|
||||
#define FLOW_GATE_DEFAULT 3
|
||||
#define GSCALE_PNOISE_DEFAULT 1e-6f
|
||||
#define GSCALE_PNOISE_DEFAULT 1.5E-03f
|
||||
|
||||
#endif // APM_BUILD_DIRECTORY
|
||||
|
||||
|
|
|
@ -748,15 +748,15 @@ void NavEKF2_core::CovariancePrediction()
|
|||
// use filtered height rate to increase wind process noise when climbing or descending
|
||||
// this allows for wind gradient effects.
|
||||
windVelSigma = dt * constrain_float(frontend._windVelProcessNoise, 0.01f, 1.0f) * (1.0f + constrain_float(frontend._wndVarHgtRateScale, 0.0f, 1.0f) * fabsf(hgtRate));
|
||||
dAngBiasSigma = dt * constrain_float(frontend._gyroBiasProcessNoise, 1e-8f, 1e-4f);
|
||||
dAngBiasSigma = dt * constrain_float(frontend._gyroBiasProcessNoise, 0.0f, 1e-4f);
|
||||
dVelBiasSigma = dt * constrain_float(frontend._accelBiasProcessNoise, 1e-6f, 1e-2f);
|
||||
dAngScaleSigma = dt * constrain_float(frontend._gyroScaleProcessNoise,1e-8f,1e-5f);
|
||||
dAngScaleSigma = dt * constrain_float(frontend._gyroScaleProcessNoise,1e-6f,1e-2f);
|
||||
magEarthSigma = dt * constrain_float(frontend._magProcessNoise, 1e-4f, 1e-2f);
|
||||
magBodySigma = dt * constrain_float(frontend._magProcessNoise, 1e-4f, 1e-2f);
|
||||
for (uint8_t i= 0; i<=8; i++) processNoise[i] = 1.0e-9f;
|
||||
for (uint8_t i= 0; i<=8; i++) processNoise[i] = 0.0f;
|
||||
for (uint8_t i=9; i<=11; i++) processNoise[i] = dAngBiasSigma;
|
||||
for (uint8_t i=10; i<=12; i++) processNoise[i] = dAngBiasSigma;
|
||||
for (uint8_t i=12; i<=14; i++) processNoise[i] = dAngScaleSigma;
|
||||
processNoise[15] = dVelBiasSigma;
|
||||
if (expectGndEffectTakeoff) {
|
||||
processNoise[15] = 0.0f;
|
||||
} else if (!filterArmed) {
|
||||
|
|
Loading…
Reference in New Issue