From 746ca91649fe09dd4674c67f3487eda3495b1b86 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 9 Jan 2018 16:19:47 -0800 Subject: [PATCH] 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) --- ArduPlane/navigation.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 22d97b8aab..1a26dfe9a9 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -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; } }