mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_NavEKF2: suppress ekf fail-to-set-origin if core disabled
This commit is contained in:
parent
353cb648f6
commit
e32a8556b2
@ -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
|
||||
bool NavEKF2::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
|
||||
@ -1111,9 +1114,6 @@ bool NavEKF2::setOriginLLH(const Location &loc)
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 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);
|
||||
|
Loading…
Reference in New Issue
Block a user