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
This commit is contained in:
Andrew Tridgell 2017-01-22 13:39:54 +11:00
parent d472fbde0c
commit 09c969477f
1 changed files with 1 additions and 1 deletions

View File

@ -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)) {