mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: fixed return of common origin
when common origin is set we should return that, not backends private origin
This commit is contained in:
parent
be5ecab686
commit
cf45dbf284
|
@ -1099,6 +1099,10 @@ bool NavEKF2::getOriginLLH(Location &loc) const
|
|||
if (!core) {
|
||||
return false;
|
||||
}
|
||||
if (common_origin_valid) {
|
||||
loc = common_EKF_origin;
|
||||
return true;
|
||||
}
|
||||
return core[primary].getOriginLLH(loc);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue