Browse Source

AP_NavEKF3: simplify taking of GPS measurements

c415-sdk
Peter Barker 4 years ago committed by Peter Barker
parent
commit
f4591faeed
  1. 5
      libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

5
libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

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

Loading…
Cancel
Save