AP_NavEKF3: allow switch to ExtNav from optflow
This commit is contained in:
parent
10eeea31e8
commit
886a7d44a7
@ -225,7 +225,7 @@ void NavEKF3_core::setAidingMode()
|
|||||||
bool bodyOdmFusionTimeout = ((imuSampleTime_ms - prevBodyVelFuseTime_ms) > 5000);
|
bool bodyOdmFusionTimeout = ((imuSampleTime_ms - prevBodyVelFuseTime_ms) > 5000);
|
||||||
// Enable switch to absolute position mode if GPS or range beacon data is available
|
// Enable switch to absolute position mode if GPS or range beacon data is available
|
||||||
// If GPS or range beacons data is not available and flow fusion has timed out, then fall-back to no-aiding
|
// If GPS or range beacons data is not available and flow fusion has timed out, then fall-back to no-aiding
|
||||||
if(readyToUseGPS() || readyToUseRangeBeacon()) {
|
if (readyToUseGPS() || readyToUseRangeBeacon() || readyToUseExtNav()) {
|
||||||
PV_AidingMode = AID_ABSOLUTE;
|
PV_AidingMode = AID_ABSOLUTE;
|
||||||
} else if (flowFusionTimeout && bodyOdmFusionTimeout) {
|
} else if (flowFusionTimeout && bodyOdmFusionTimeout) {
|
||||||
PV_AidingMode = AID_NONE;
|
PV_AidingMode = AID_NONE;
|
||||||
|
Loading…
Reference in New Issue
Block a user