mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: Don't Switch to DCM to get Better GPS if DCM Isn't Using GPS
Look at the parameter to see if DCM uses GPS; if not don't prefer DCM for using GPS.
This commit is contained in:
parent
81d4804d53
commit
03ae94706e
|
@ -1974,6 +1974,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const
|
|||
|
||||
// Handle loss of global position when we still have a GPS fix
|
||||
if (hal.util->get_soft_armed() &&
|
||||
(_gps_use != GPSUse::Disable) &&
|
||||
should_use_gps &&
|
||||
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D &&
|
||||
(!filt_state.flags.using_gps || !filt_state.flags.horiz_pos_abs)) {
|
||||
|
|
Loading…
Reference in New Issue