AP_NavEKF3: restrict setting of EKF origin

only allow EKF origin to be set if EKx_GPS_TYPE is set to 3, which is
used for indoor operation
This commit is contained in:
Andrew Tridgell 2019-07-27 15:28:27 +10:00
parent 5db41147ed
commit 3818d8ecda

View File

@ -1111,6 +1111,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;
}