Plane: reset groundspeed_undershoot value when GPS is lost

If we lose GPS lock the gndspd undershoot value gets stuck at the last calculated value forever (until GPS locks again)
This commit is contained in:
Tom Pittenger 2018-01-09 16:19:47 -08:00 committed by Tom Pittenger
parent 1ef0f27786
commit 746ca91649

View File

@ -163,6 +163,8 @@ void Plane::calc_gndspeed_undershoot()
float gndSpdFwd = yawVect * gndVel;
groundspeed_undershoot = (aparm.min_gndspeed_cm > 0) ? (aparm.min_gndspeed_cm - gndSpdFwd*100) : 0;
}
} else {
groundspeed_undershoot = 0;
}
}