AP_NavEKF3: getLLH fix when no GPS available

This commit is contained in:
Randy Mackay 2020-04-24 15:04:39 +09:00
parent 2919491298
commit 91a79543c9

View File

@ -345,6 +345,8 @@ bool NavEKF3_core::getLLH(struct Location &loc) const
return true;
} else {
// if no GPS fix, provide last known position before entering the mode
loc.lat = EKF_origin.lat;
loc.lng = EKF_origin.lng;
loc.offset(lastKnownPositionNE.x, lastKnownPositionNE.y);
return false;
}