mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
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:
parent
e8ab62f6e5
commit
6a24bdec05
@ -390,10 +390,14 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
|||||||
// we have integrated over
|
// we have integrated over
|
||||||
_ra_deltat += deltat;
|
_ra_deltat += deltat;
|
||||||
|
|
||||||
if (!have_gps()) {
|
if (!have_gps() || _gps->num_sats < 6) {
|
||||||
// no GPS, or no lock. We assume zero velocity. This at
|
// no GPS, or not a good lock. From experience we need at
|
||||||
// least means we can cope with gyro drift while sitting
|
// least 6 satellites to get a really reliable velocity number
|
||||||
// on a bench with no GPS lock
|
// 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) {
|
if (_ra_deltat < 0.2) {
|
||||||
// not enough time has accumulated
|
// not enough time has accumulated
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user