mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF : remove onGround airspeed detect bug
This commit is contained in:
parent
a507fa7570
commit
8bc14d09b2
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user