AP_NavEKF3: suppress ekf fail-to-set-origin if core disabled

This commit is contained in:
Randy Mackay 2019-10-17 16:52:07 +09:00
parent e32a8556b2
commit 63309c6925

View File

@ -1127,6 +1127,9 @@ bool NavEKF3::getOriginLLH(int8_t instance, struct Location &loc) const
// Returns false if the filter has rejected the attempt to set the origin
bool NavEKF3::setOriginLLH(const Location &loc)
{
if (!core) {
return false;
}
if (_fusionModeGPS != 3) {
// we don't allow setting of the EKF origin unless we are
// flying in non-GPS mode. This is to prevent accidental set
@ -1134,9 +1137,6 @@ bool NavEKF3::setOriginLLH(const Location &loc)
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 refusing set origin");
return false;
}
if (!core) {
return false;
}
bool ret = false;
for (uint8_t i=0; i<num_cores; i++) {
ret |= core[i].setOriginLLH(loc);