mirror of https://github.com/ArduPilot/ardupilot
parent
b7c6267ec6
commit
7b0cf32ae3
|
@ -670,6 +670,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;
|
||||
|
|
|
@ -439,7 +439,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) {
|
||||
|
|
Loading…
Reference in New Issue