mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_NavEKF2: fix reporting of optical flow use status
This commit is contained in:
parent
ed9ecb28fb
commit
b0072b587c
@ -407,7 +407,7 @@ void NavEKF2_core::updateFilterStatus(void)
|
||||
bool doingNormalGpsNav = !posTimeout && (PV_AidingMode == AID_ABSOLUTE);
|
||||
bool someVertRefData = (!velTimeout && useGpsVertVel) || !hgtTimeout;
|
||||
bool someHorizRefData = !(velTimeout && posTimeout && tasTimeout) || doingFlowNav;
|
||||
bool optFlowNavPossible = flowDataValid && (frontend->_fusionModeGPS == 3) && delAngBiasLearned;
|
||||
bool optFlowNavPossible = flowDataValid && delAngBiasLearned;
|
||||
bool gpsNavPossible = !gpsNotAvailable && gpsGoodToAlign && delAngBiasLearned;
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user