From 659904bf6538350d3d29554d5f9abc8234fd1e14 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 26 Feb 2015 09:15:16 -0800 Subject: [PATCH] Plane: sped up is_flying filter since it is running at only 1Hz --- ArduPlane/ArduPlane.pde | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 3a4f1cd505..b63cdbdf76 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1571,19 +1571,19 @@ static void determine_is_flying(void) } // low-pass the result. - isFlyingProbability = (0.8 * isFlyingProbability) + (0.2*(float)isFlyingBool); + isFlyingProbability = (0.6f * isFlyingProbability) + (0.4f * (float)isFlyingBool); } static bool is_flying(void) { if(arming.is_armed()) { // when armed, assume we're flying unless we probably aren't - return (isFlyingProbability >= 0.1); + return (isFlyingProbability >= 0.1f); } else { // when disarmed, assume we're not flying unless we probably are - return (isFlyingProbability >= 0.9); + return (isFlyingProbability >= 0.9f); } }