AP_NavEKF: Report correct horiz vel sol'n status during optical flow nav

This commit is contained in:
priseborough 2015-01-03 08:41:09 +11:00 committed by Andrew Tridgell
parent 584fa9b4bf
commit e6474d676e

View File

@ -4517,7 +4517,7 @@ void NavEKF::getFilterStatus(uint8_t &status) const
bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
bool notDeadReckoning = !constVelMode && !constPosMode;
bool someVertRefData = (!velTimeout && (_fusionModeGPS == 0)) || !hgtTimeout;
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout);
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
status = (!state.quat.is_nan()<<0 | // attitude valid (we need a better check)
(someHorizRefData && notDeadReckoning)<<1 | // horizontal velocity estimate valid
someVertRefData<<2 | // vertical velocity estimate valid