mirror of https://github.com/ArduPilot/ardupilot
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:
parent
25ee6de4bd
commit
a4d4c62c45
|
@ -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;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue