From 35ddaa2d4220eb38349df7b045bce659900bba8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 29 Jul 2019 08:55:39 +1000 Subject: [PATCH] AP_NavEKF2: review fixes thanks Paul! --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 3 +++ libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 1 - 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index d58a0941b2..9309ee34d8 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -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; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index 4b26313979..17dc9c0883 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -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) {