Browse Source

AP_NavEKF2: review fixes

thanks Paul!
master
Andrew Tridgell 6 years ago
parent
commit
e7163afe06
  1. 3
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 1
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

3
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -684,6 +684,9 @@ bool NavEKF2::InitialiseFilter(void) @@ -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;

1
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -432,7 +432,6 @@ bool NavEKF2_core::setOriginLLH(const Location &loc) @@ -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) {

Loading…
Cancel
Save