Browse Source

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

master
Randy Mackay 5 years ago
parent
commit
63309c6925
  1. 6
      libraries/AP_NavEKF3/AP_NavEKF3.cpp

6
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -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 // Returns false if the filter has rejected the attempt to set the origin
bool NavEKF3::setOriginLLH(const Location &loc) bool NavEKF3::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
@ -1134,9 +1137,6 @@ bool NavEKF3::setOriginLLH(const Location &loc)
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 refusing set origin"); gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 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);

Loading…
Cancel
Save