Browse Source

AP_NavEKF: Remove bug preventing external selection of optical flow mode

master
Paul Riseborough 10 years ago committed by Andrew Tridgell
parent
commit
cb59570938
  1. 2
      libraries/AP_NavEKF/AP_NavEKF.cpp

2
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -3700,11 +3700,11 @@ uint8_t NavEKF::setInhibitGPS(void) @@ -3700,11 +3700,11 @@ uint8_t NavEKF::setInhibitGPS(void)
return 0;
}
if (optFlowDataPresent()) {
_fusionModeGPS = 3;
return 2;
} else {
return 1;
}
_fusionModeGPS = 3;
}
// return the horizontal speed limit in m/s set by optical flow sensor limits

Loading…
Cancel
Save