From 09c969477ff66c39c6ee3163eea6bed5ab065e2c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 22 Jan 2017 13:39:54 +1100 Subject: [PATCH] AP_AHRS: fixed fallback to DCM for get_position this fixes dead-reckoning on fixed wing on GPS loss, and fallback to DCM on loss of EKF position in fixed wing This was broken by the EKF3 merge --- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 1834e6bf3f..ec6703a6bf 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -323,7 +323,7 @@ bool AP_AHRS_NavEKF::get_position(struct Location &loc) const Location origin; switch (active_EKF_type()) { case EKF_TYPE_NONE: - return false; + return AP_AHRS_DCM::get_position(loc); case EKF_TYPE2: if (EKF2.getLLH(loc) && EKF2.getPosD(-1,ned_pos.z) && EKF2.getOriginLLH(origin)) {