AP_NavEKF2: set origin on all cores

when EKF origin is set, make sure it is set on all cores
This commit is contained in:
Andrew Tridgell 2019-07-27 15:29:15 +10:00
parent 8ee28b4a66
commit e9d51bb0c7
1 changed files with 6 additions and 1 deletions

View File

@ -1034,7 +1034,12 @@ bool NavEKF2::setOriginLLH(const Location &loc)
if (!core) {
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