AP_NavEKF3: simplify taking of GPS measurements

This commit is contained in:
Peter Barker 2021-03-05 14:13:32 +11:00 committed by Peter Barker
parent 8aabf7c22a
commit f4591faeed
1 changed files with 1 additions and 4 deletions

View File

@ -339,10 +339,7 @@ bool NavEKF3_core::getGPSLLH(struct Location &loc) const
{
const auto &gps = dal.gps();
if ((gps.status(selected_gps) >= AP_DAL_GPS::GPS_OK_FIX_3D)) {
const struct Location &gpsloc = gps.location(selected_gps);
loc = gpsloc;
loc.relative_alt = 0;
loc.terrain_alt = 0;
loc = gps.location(selected_gps);
return true;
}
return false;