AP_NavEKF2: 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 1fd6c0c00c
commit a75e2e1c0e
1 changed files with 7 additions and 0 deletions

View File

@ -1024,6 +1024,13 @@ 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 (_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, "EKF2 refusing set origin");
return false;
}
if (!core) {
return false;
}