Browse Source

AP_NavEKF: Fix bug preventing the non-GPS mode being selected externally

When on the ground it is likely the flow sensor will be returning  data that does not meet the minimum quality requirements selected.
The previous check was for the presence of valid data. This has been loosened to look for the presence of data.
When the vehicle becomes airborne, the quality of flow data normally improves as the image comes into focus.
master
priseborough 10 years ago committed by Randy Mackay
parent
commit
a16253796f
  1. 2
      libraries/AP_NavEKF/AP_NavEKF.cpp

2
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -3624,7 +3624,7 @@ uint8_t NavEKF::setInhibitGPS(void) @@ -3624,7 +3624,7 @@ uint8_t NavEKF::setInhibitGPS(void)
if(!staticMode) {
return 0;
}
if (useOptFlow()) {
if (optFlowDataPresent()) {
gpsInhibitMode = 2;
return 2;
} else {

Loading…
Cancel
Save