mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF3: review fixes
thanks Paul!
This commit is contained in:
parent
056b96ab7a
commit
6f9553479b
@ -700,6 +700,9 @@ bool NavEKF3::InitialiseFilter(void)
|
|||||||
// Set the primary initially to be the lowest index
|
// Set the primary initially to be the lowest index
|
||||||
primary = 0;
|
primary = 0;
|
||||||
|
|
||||||
|
// invalidate shared origin
|
||||||
|
common_origin_valid = false;
|
||||||
|
|
||||||
// initialise the cores. We return success only if all cores
|
// initialise the cores. We return success only if all cores
|
||||||
// initialise successfully
|
// initialise successfully
|
||||||
bool ret = true;
|
bool ret = true;
|
||||||
|
@ -484,7 +484,6 @@ bool NavEKF3_core::setOriginLLH(const Location &loc)
|
|||||||
// Set the NED origin to be used until the next filter reset
|
// Set the NED origin to be used until the next filter reset
|
||||||
void NavEKF3_core::setOrigin(const Location &loc)
|
void NavEKF3_core::setOrigin(const Location &loc)
|
||||||
{
|
{
|
||||||
// assume origin at current GPS location (no averaging)
|
|
||||||
EKF_origin = loc;
|
EKF_origin = loc;
|
||||||
// if flying, correct for height change from takeoff so that the origin is at field elevation
|
// if flying, correct for height change from takeoff so that the origin is at field elevation
|
||||||
if (inFlight) {
|
if (inFlight) {
|
||||||
|
Loading…
Reference in New Issue
Block a user