AP_NavEKF2: review fixes

thanks Paul!
This commit is contained in:
Andrew Tridgell 2019-07-29 08:55:39 +10:00
parent 451fe840ee
commit e7163afe06
2 changed files with 3 additions and 1 deletions

View File

@ -684,6 +684,9 @@ bool NavEKF2::InitialiseFilter(void)
primary = 0;
}
// invalidate shared origin
common_origin_valid = false;
// initialise the cores. We return success only if all cores
// initialise successfully
bool ret = true;

View File

@ -432,7 +432,6 @@ bool NavEKF2_core::setOriginLLH(const Location &loc)
// Set the NED origin to be used until the next filter reset
void NavEKF2_core::setOrigin(const Location &loc)
{
// assume origin at current GPS location (no averaging)
EKF_origin = loc;
// if flying, correct for height change from takeoff so that the origin is at field elevation
if (inFlight) {