Browse Source

AP_NavEKF3: apply min GPS accuracy at measurement point

this fixes an issue a RTK GPS gives 1cm horizontal and vertical
accuracy and that causes the variances to get too small
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
44d5a923cc
  1. 3
      libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

3
libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

@ -564,6 +564,7 @@ void NavEKF3_core::readGpsData() @@ -564,6 +564,7 @@ void NavEKF3_core::readGpsData()
} else {
gpsSpdAccuracy = MAX(gpsSpdAccuracy,gpsSpdAccRaw);
gpsSpdAccuracy = MIN(gpsSpdAccuracy,50.0f);
gpsSpdAccuracy = MAX(gpsSpdAccuracy,frontend->_gpsHorizVelNoise);
}
gpsPosAccuracy *= (1.0f - alpha);
float gpsPosAccRaw;
@ -572,6 +573,7 @@ void NavEKF3_core::readGpsData() @@ -572,6 +573,7 @@ void NavEKF3_core::readGpsData()
} else {
gpsPosAccuracy = MAX(gpsPosAccuracy,gpsPosAccRaw);
gpsPosAccuracy = MIN(gpsPosAccuracy,100.0f);
gpsPosAccuracy = MAX(gpsPosAccuracy, frontend->_gpsHorizPosNoise);
}
gpsHgtAccuracy *= (1.0f - alpha);
float gpsHgtAccRaw;
@ -580,6 +582,7 @@ void NavEKF3_core::readGpsData() @@ -580,6 +582,7 @@ void NavEKF3_core::readGpsData()
} else {
gpsHgtAccuracy = MAX(gpsHgtAccuracy,gpsHgtAccRaw);
gpsHgtAccuracy = MIN(gpsHgtAccuracy,100.0f);
gpsHgtAccuracy = MAX(gpsHgtAccuracy, 1.5f * frontend->_gpsHorizPosNoise);
}
// check if we have enough GPS satellites and increase the gps noise scaler if we don't

Loading…
Cancel
Save