mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF: Remove bug preventing external selection of optical flow mode
This commit is contained in:
parent
d61848817b
commit
cb59570938
|
@ -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…
Reference in New Issue