Browse Source

AP_NavEKF: Prevent position drift between arming and takeoff when using OF

mission-4.1.18
Paul Riseborough 10 years ago committed by Randy Mackay
parent
commit
610595bfb9
  1. 1
      libraries/AP_NavEKF/AP_NavEKF.cpp

1
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -1005,6 +1005,7 @@ void NavEKF::SelectFlowFusion() @@ -1005,6 +1005,7 @@ void NavEKF::SelectFlowFusion()
flowRadXY[0] = 0.0f;
flowRadXY[1] = 0.0f;
omegaAcrossFlowTime.zero();
flowDataValid = true;
}
// If the flow measurements have been rejected for too long and we are relying on them, then revert to constant position mode
if ((flowSensorTimeout || flowFusionTimeout) && PV_AidingMode == AID_RELATIVE) {

Loading…
Cancel
Save