From f514e76f52cdc5787e27928bc38296f1158c3291 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Jun 2016 11:49:29 +1000 Subject: [PATCH] Plane: reset ground_start_count if we lose 3D fix thanks to Michael for this suggestion --- ArduPlane/ArduPlane.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 5cc21d4a4f..c04eaadb3a 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -491,6 +491,9 @@ void Plane::update_GPS_10Hz(void) // update wind estimate ahrs.estimate_wind(); + } else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) { + // lost 3D fix, start again + ground_start_count = 5; } calc_gndspeed_undershoot();