Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_AHRS: prevent DCM fallback when losing GPS #25408

Closed
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1930,19 +1930,19 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const
should_use_gps = true;
}
#endif
const bool have_gps = AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D;
if (hal.util->get_soft_armed() &&
(!filt_state.flags.using_gps ||
!filt_state.flags.horiz_pos_abs) &&
should_use_gps &&
AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
should_use_gps && have_gps) {
// if the EKF is not fusing GPS or doesn't have a 2D fix
// and we have a 3D lock, then plane and rover would
// prefer to use the GPS position from DCM. This is a
// safety net while some issues with the EKF get sorted
// out
return EKFType::DCM;
}
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode && have_gps) {
return EKFType::DCM;
}
if (!filt_state.flags.attitude ||
Expand Down
Loading