Browse Source

AP_AHRS: removed the 6 sats min

this would put us into dead-reckoning mode
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
fe47990dab
  1. 2
      libraries/AP_AHRS/AP_AHRS_DCM.cpp

2
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -390,7 +390,7 @@ AP_AHRS_DCM::drift_correction(float deltat) @@ -390,7 +390,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
// we have integrated over
_ra_deltat += deltat;
if (!have_gps() || _gps->num_sats < 6) {
if (!have_gps()) {
// 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.

Loading…
Cancel
Save