mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_NavEKF3: set origin on all cores
when EKF origin is set, make sure it is set on all cores
This commit is contained in:
parent
e9d51bb0c7
commit
d43a386f83
@ -1053,7 +1053,12 @@ bool NavEKF3::setOriginLLH(const Location &loc)
|
|||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return core[primary].setOriginLLH(loc);
|
bool ret = false;
|
||||||
|
for (uint8_t i=0; i<num_cores; i++) {
|
||||||
|
ret |= core[i].setOriginLLH(loc);
|
||||||
|
}
|
||||||
|
// return true if any core accepts the new origin
|
||||||
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return estimated height above ground level
|
// return estimated height above ground level
|
||||||
|
Loading…
Reference in New Issue
Block a user