mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2: Enable simultaneous optical flow and GPS use
Enables simultaneous use of GPS and optical flow data with automatic fallback to relative position mode if GPS is lost and automatic switch-up to absolute position status if GPS gained/re-gained.
This commit is contained in:
parent
f135ca5ae7
commit
f9018fcc1b
@ -178,7 +178,11 @@ void NavEKF2_core::setAidingMode()
|
|||||||
bool flowSensorTimeout = ((imuSampleTime_ms - flowValidMeaTime_ms) > 5000);
|
bool flowSensorTimeout = ((imuSampleTime_ms - flowValidMeaTime_ms) > 5000);
|
||||||
// Check if the fusion has timed out (flow measurements have been rejected for too long)
|
// Check if the fusion has timed out (flow measurements have been rejected for too long)
|
||||||
bool flowFusionTimeout = ((imuSampleTime_ms - prevFlowFuseTime_ms) > 5000);
|
bool flowFusionTimeout = ((imuSampleTime_ms - prevFlowFuseTime_ms) > 5000);
|
||||||
if (flowSensorTimeout || flowFusionTimeout) {
|
// Enable switch to absolute position mode if GPS is available
|
||||||
|
// If GPS is not available and flow fusion has timed out, then fall-back to no-aiding
|
||||||
|
if((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && !gpsInhibit) {
|
||||||
|
PV_AidingMode = AID_ABSOLUTE;
|
||||||
|
} else if (flowSensorTimeout || flowFusionTimeout) {
|
||||||
PV_AidingMode = AID_NONE;
|
PV_AidingMode = AID_NONE;
|
||||||
}
|
}
|
||||||
} else if (PV_AidingMode == AID_ABSOLUTE) {
|
} else if (PV_AidingMode == AID_ABSOLUTE) {
|
||||||
|
@ -59,8 +59,8 @@ void NavEKF2_core::SelectFlowFusion()
|
|||||||
EstimateTerrainOffset();
|
EstimateTerrainOffset();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Fuse optical flow data into the main filter if not excessively tilted and we are in the correct mode
|
// Fuse optical flow data into the main filter
|
||||||
if (flowDataToFuse && tiltOK && PV_AidingMode == AID_RELATIVE)
|
if (flowDataToFuse && tiltOK)
|
||||||
{
|
{
|
||||||
// Set the flow noise used by the fusion processes
|
// Set the flow noise used by the fusion processes
|
||||||
R_LOS = sq(MAX(frontend->_flowNoise, 0.05f));
|
R_LOS = sq(MAX(frontend->_flowNoise, 0.05f));
|
||||||
|
Loading…
Reference in New Issue
Block a user