AP_NavEKF2: 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
This commit is contained in:
parent
2f85bd54ea
commit
f0781f15a1
@ -511,6 +511,7 @@ void NavEKF2_core::readGpsData()
|
|||||||
} else {
|
} else {
|
||||||
gpsSpdAccuracy = MAX(gpsSpdAccuracy,gpsSpdAccRaw);
|
gpsSpdAccuracy = MAX(gpsSpdAccuracy,gpsSpdAccRaw);
|
||||||
gpsSpdAccuracy = MIN(gpsSpdAccuracy,50.0f);
|
gpsSpdAccuracy = MIN(gpsSpdAccuracy,50.0f);
|
||||||
|
gpsSpdAccuracy = MAX(gpsSpdAccuracy,frontend->_gpsHorizVelNoise);
|
||||||
}
|
}
|
||||||
gpsPosAccuracy *= (1.0f - alpha);
|
gpsPosAccuracy *= (1.0f - alpha);
|
||||||
float gpsPosAccRaw;
|
float gpsPosAccRaw;
|
||||||
@ -519,6 +520,7 @@ void NavEKF2_core::readGpsData()
|
|||||||
} else {
|
} else {
|
||||||
gpsPosAccuracy = MAX(gpsPosAccuracy,gpsPosAccRaw);
|
gpsPosAccuracy = MAX(gpsPosAccuracy,gpsPosAccRaw);
|
||||||
gpsPosAccuracy = MIN(gpsPosAccuracy,100.0f);
|
gpsPosAccuracy = MIN(gpsPosAccuracy,100.0f);
|
||||||
|
gpsPosAccuracy = MAX(gpsPosAccuracy, frontend->_gpsHorizPosNoise);
|
||||||
}
|
}
|
||||||
gpsHgtAccuracy *= (1.0f - alpha);
|
gpsHgtAccuracy *= (1.0f - alpha);
|
||||||
float gpsHgtAccRaw;
|
float gpsHgtAccRaw;
|
||||||
@ -527,6 +529,7 @@ void NavEKF2_core::readGpsData()
|
|||||||
} else {
|
} else {
|
||||||
gpsHgtAccuracy = MAX(gpsHgtAccuracy,gpsHgtAccRaw);
|
gpsHgtAccuracy = MAX(gpsHgtAccuracy,gpsHgtAccRaw);
|
||||||
gpsHgtAccuracy = MIN(gpsHgtAccuracy,100.0f);
|
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
|
// check if we have enough GPS satellites and increase the gps noise scaler if we don't
|
||||||
|
Loading…
Reference in New Issue
Block a user