AP_NavEKF2: Update status reporting to handle no-magnetometer startup

This commit is contained in:
Paul Riseborough 2016-05-21 11:54:26 +10:00 committed by Andrew Tridgell
parent 9aa3cdfaae
commit 38d61f5281
1 changed files with 2 additions and 2 deletions

View File

@ -459,8 +459,8 @@ void NavEKF2_core::getFilterStatus(nav_filter_status &status) const
bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout; bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav; bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
bool optFlowNavPossible = flowDataValid && (frontend->_fusionModeGPS == 3); bool optFlowNavPossible = flowDataValid && (frontend->_fusionModeGPS == 3);
bool gpsNavPossible = !gpsNotAvailable && (PV_AidingMode == AID_ABSOLUTE) && gpsGoodToAlign; bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign;
bool filterHealthy = healthy() && tiltAlignComplete && yawAlignComplete; bool filterHealthy = healthy() && tiltAlignComplete && (yawAlignComplete || (!use_compass() && (PV_AidingMode == AID_NONE)));
// If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks // If GPS height usage is specified, height is considered to be inaccurate until the GPS passes all checks
bool hgtNotAccurate = (frontend->_altSource == 2) && !validOrigin; bool hgtNotAccurate = (frontend->_altSource == 2) && !validOrigin;