AP_AHRS: require at least 6 satellites to use the GPS for velocity

logs of a recent flight show the velocity estimate can be very poor if
the GPS can see 5 satellites or less
This commit is contained in:
Andrew Tridgell 2012-11-05 20:06:44 +11:00
parent e8ab62f6e5
commit 6a24bdec05
1 changed files with 8 additions and 4 deletions

View File

@ -390,10 +390,14 @@ AP_AHRS_DCM::drift_correction(float deltat)
// we have integrated over
_ra_deltat += deltat;
if (!have_gps()) {
// no GPS, or no lock. We assume zero velocity. This at
// least means we can cope with gyro drift while sitting
// on a bench with no GPS lock
if (!have_gps() || _gps->num_sats < 6) {
// no GPS, or not a good lock. From experience we need at
// least 6 satellites to get a really reliable velocity number
// from the GPS.
//
// As a fallback we use the fixed wing acceleration correction
// if we have an airspeed estimate (which we only have if
// _fly_forward is set), otherwise no correction
if (_ra_deltat < 0.2) {
// not enough time has accumulated
return;