AP_NavEKF : remove onGround airspeed detect bug

This commit is contained in:
Paul Riseborough 2014-01-01 14:37:30 +11:00 committed by Andrew Tridgell
parent a507fa7570
commit 8bc14d09b2

View File

@ -1956,7 +1956,11 @@ bool NavEKF::getLLH(struct Location &loc)
void NavEKF::OnGroundCheck()
{
onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
bool noAirSpd;
bool noGndSpd;
noAirSpd = (_ahrs.airspeed_estimate_true(&VtasMeas) < 8.0f);
noGndSpd = ((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f);
onGround = (noAirSpd && noGndSpd);
}
void NavEKF::CovarianceInit()