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

This commit is contained in:
Randy Mackay 2019-10-17 16:51:55 +09:00
parent 353cb648f6
commit e32a8556b2
1 changed files with 3 additions and 3 deletions

View File

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