Browse Source

AP_NavEKF2: Open up tuning limits

Done to assist tuning assessments
master
Paul Riseborough 9 years ago committed by Andrew Tridgell
parent
commit
dddc213836
  1. 16
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

16
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -667,12 +667,12 @@ void NavEKF2_core::CovariancePrediction() @@ -667,12 +667,12 @@ 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, 0.0f, 1e-4f);
dVelBiasSigma = dt * constrain_float(frontend->_accelBiasProcessNoise, 1e-6f, 1e-2f);
dAngScaleSigma = dt * constrain_float(frontend->_gyroScaleProcessNoise,1e-6f,1e-2f);
magEarthSigma = dt * constrain_float(frontend->_magProcessNoise, 1e-4f, 1e-1f);
magBodySigma = dt * constrain_float(frontend->_magProcessNoise, 1e-4f, 1e-1f);
windVelSigma = dt * constrain_float(frontend->_windVelProcessNoise, 0.0f, 1.0f) * (1.0f + constrain_float(frontend->_wndVarHgtRateScale, 0.0f, 1.0f) * fabsf(hgtRate));
dAngBiasSigma = dt * constrain_float(frontend->_gyroBiasProcessNoise, 0.0f, 1.0f);
dVelBiasSigma = dt * constrain_float(frontend->_accelBiasProcessNoise, 0.0f, 1.0f);
dAngScaleSigma = dt * constrain_float(frontend->_gyroScaleProcessNoise, 0.0f, 1.0f);
magEarthSigma = dt * constrain_float(frontend->_magProcessNoise, 0.0f, 1.0f);
magBodySigma = dt * constrain_float(frontend->_magProcessNoise, 0.0f, 1.0f);
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=12; i<=14; i++) processNoise[i] = dAngScaleSigma;
@ -705,9 +705,9 @@ void NavEKF2_core::CovariancePrediction() @@ -705,9 +705,9 @@ void NavEKF2_core::CovariancePrediction()
day_s = stateStruct.gyro_scale.y;
daz_s = stateStruct.gyro_scale.z;
dvz_b = stateStruct.accel_zbias;
float _gyrNoise = constrain_float(frontend->_gyrNoise, 1e-4f, 1e-2f);
float _accNoise = constrain_float(frontend->_accNoise, 1e-2f, 1.0f);
float _gyrNoise = constrain_float(frontend->_gyrNoise, 0.0f, 1.0f);
daxNoise = dayNoise = dazNoise = sq(dt*_gyrNoise);
float _accNoise = constrain_float(frontend->_accNoise, 0.0f, 1.0f);
dvxNoise = dvyNoise = dvzNoise = sq(dt*_accNoise);
// calculate the predicted covariance due to inertial sensor error propagation

Loading…
Cancel
Save