mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Allow smaller dvel bias state variances for improved tuning
This commit is contained in:
parent
ffce6fab70
commit
942a1f329f
|
@ -1885,11 +1885,11 @@ void NavEKF3_core::ConstrainVariances()
|
||||||
zeroRows(P,10,12);
|
zeroRows(P,10,12);
|
||||||
}
|
}
|
||||||
|
|
||||||
const ftype minStateVarTarget = 1E-8;
|
const ftype minStateVarTarget = 1E-11;
|
||||||
if (!inhibitDelVelBiasStates) {
|
if (!inhibitDelVelBiasStates) {
|
||||||
|
|
||||||
// Find the maximum delta velocity bias state variance and request a covariance reset if any variance is below the safe minimum
|
// Find the maximum delta velocity bias state variance and request a covariance reset if any variance is below the safe minimum
|
||||||
const ftype minSafeStateVar = 1e-9;
|
const ftype minSafeStateVar = minStateVarTarget * 0.1f;
|
||||||
ftype maxStateVar = minSafeStateVar;
|
ftype maxStateVar = minSafeStateVar;
|
||||||
bool resetRequired = false;
|
bool resetRequired = false;
|
||||||
for (uint8_t stateIndex=13; stateIndex<=15; stateIndex++) {
|
for (uint8_t stateIndex=13; stateIndex<=15; stateIndex++) {
|
||||||
|
|
Loading…
Reference in New Issue