diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 9c7552decf..561decbcf4 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1043,6 +1043,13 @@ 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 (_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 + // of EKF origin with invalid position or height + gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 refusing set origin"); + return false; + } if (!core) { return false; }