AP_NavEKF2: Enable entry into relative position mode on start-up
This commit is contained in:
parent
e0b8c54194
commit
ed9ecb28fb
@ -170,7 +170,7 @@ void NavEKF2_core::setAidingMode()
|
||||
// GPS aiding is the perferred option unless excluded by the user
|
||||
if((frontend->_fusionModeGPS) != 3 && readyToUseGPS() && filterIsStable && !gpsInhibit) {
|
||||
PV_AidingMode = AID_ABSOLUTE;
|
||||
} else if ((frontend->_fusionModeGPS == 3) && optFlowDataPresent()) {
|
||||
} else if (optFlowDataPresent() && filterIsStable) {
|
||||
PV_AidingMode = AID_RELATIVE;
|
||||
}
|
||||
} else if (PV_AidingMode == AID_RELATIVE) {
|
||||
|
Loading…
Reference in New Issue
Block a user