mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_NavEKF2: allow setOrigin when using GPS
this allows for use of a common origin between backends, and aligns with EKF3 behaviour
This commit is contained in:
parent
777aab6e0c
commit
3444de06b1
@ -1113,11 +1113,9 @@ bool NavEKF2::setOriginLLH(const Location &loc)
|
|||||||
if (!core) {
|
if (!core) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (_fusionModeGPS != 3 || common_origin_valid) {
|
if (common_origin_valid) {
|
||||||
// we don't allow setting of the EKF origin if using GPS
|
// we don't allow setting of the EKF origin if the EKF origin
|
||||||
// or if the EKF origin has already been set.
|
// has already been set.
|
||||||
// This is to prevent accidental setting of EKF origin with an
|
|
||||||
// invalid position or height or causing upsets from a shifting origin.
|
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF2 refusing set origin");
|
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "EKF2 refusing set origin");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user