From ada0dd5504e11b39d8de7f24000fb0aee78133f0 Mon Sep 17 00:00:00 2001
From: Andrew Tridgell <tridge@samba.org>
Date: Fri, 17 Jan 2014 10:29:28 +1100
Subject: [PATCH] Plane: check both ground and airspeed in autocal test

when the airspeed ratio is far too low we were not raising it as the
airspeed was never getting above the minimum airspeed

Pair-Programmed-With: Jon Challinger
---
 ArduPlane/ArduPlane.pde | 11 +++++++++--
 1 file changed, 9 insertions(+), 2 deletions(-)

diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 3dab4fa70..44a47a80b 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -1014,9 +1014,16 @@ static void airspeed_ratio_update(void)
 {
     if (!airspeed.enabled() ||
         g_gps->status() < GPS::GPS_OK_FIX_3D ||
-        g_gps->ground_speed_cm < 400 ||
-        airspeed.get_airspeed() < aparm.airspeed_min) {
+        g_gps->ground_speed_cm < 400) {
         // don't calibrate when not moving
+        return;        
+    }
+    if (airspeed.get_airspeed() < aparm.airspeed_min && 
+        g_gps->ground_speed_cm < (uint32_t)aparm.airspeed_min*100) {
+        // don't calibrate when flying below the minimum airspeed. We
+        // check both airspeed and ground speed to catch cases where
+        // the airspeed ratio is way too low, which could lead to it
+        // never coming up again
         return;
     }
     if (abs(ahrs.roll_sensor) > roll_limit_cd ||
-- 
GitLab