From 0a5de21dc72957c7ea3fac07fbbb690ffa33429d Mon Sep 17 00:00:00 2001 From: priseborough Date: Sun, 21 Dec 2014 21:30:52 +1100 Subject: [PATCH] AP_NavEKF: Fix bug in reporting of solution status Because synthetic position measurements at 0,0 are fused during position hold mode, a position timeout cannot be used as the only means of detecting position solution status. --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index f67fdf5dd8..f1f1f4188b 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -4551,7 +4551,7 @@ void NavEKF::getFilterStatus(uint8_t &status) const !(velTimeout && tasTimeout)<<1 | !((velTimeout && hgtTimeout) || (hgtTimeout && _fusionModeGPS > 0))<<2 | ((gpsInhibitMode == 2 && flowDataValid) || (!tasTimeout && assume_zero_sideslip()))<<3 | - !posTimeout<<4 | + !(posTimeout || gpsInhibitMode == 1)<<4 | !hgtTimeout<<5 | !inhibitGndState<<6 | posHoldMode<<7);