mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_NavEKF: Increase divergence test margin based on analysis of more user flight logs
Analysis of copter logs has shown cases with a healthy EKF where spikes in EKF4.DS of up to 25% of the threshold have occurred. A value of closer to 10% for normal operation is preferred.
This commit is contained in:
parent
055d8fe7aa
commit
edc79ca2a4
@ -3402,7 +3402,7 @@ void NavEKF::checkDivergence()
|
||||
float tempLength = tempVec.length();
|
||||
if (tempLength != 0.0f) {
|
||||
float temp = constrain_float((P[10][10] + P[11][11] + P[12][12]),1e-12f,1e-8f);
|
||||
scaledDeltaGyrBiasLgth = (1e-6f / temp) * tempVec.length() / dtIMU;
|
||||
scaledDeltaGyrBiasLgth = (5e-7f / temp) * tempVec.length() / dtIMU;
|
||||
}
|
||||
bool divergenceDetected = (scaledDeltaGyrBiasLgth > 1.0f);
|
||||
lastGyroBias = state.gyro_bias;
|
||||
|
Loading…
Reference in New Issue
Block a user