mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF3: review fixes
thanks Paul!
This commit is contained in:
parent
e7163afe06
commit
04944fa6ce
@ -712,6 +712,9 @@ bool NavEKF3::InitialiseFilter(void)
|
||||
// Set the primary initially to be the lowest index
|
||||
primary = 0;
|
||||
|
||||
// invalidate shared origin
|
||||
common_origin_valid = false;
|
||||
|
||||
// initialise the cores. We return success only if all cores
|
||||
// initialise successfully
|
||||
bool ret = true;
|
||||
|
@ -481,7 +481,6 @@ bool NavEKF3_core::setOriginLLH(const Location &loc)
|
||||
// Set the NED origin to be used until the next filter reset
|
||||
void NavEKF3_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
Block a user