mirror of https://github.com/ArduPilot/ardupilot
Copter: AP_Arming: Added check for EKF origin altitude
This commit is contained in:
parent
d964fa2307
commit
3c83eecf78
|
@ -107,7 +107,7 @@ bool Copter::far_from_EKF_origin(const Location& loc)
|
|||
{
|
||||
// check distance to EKF origin
|
||||
Location ekf_origin;
|
||||
if (ahrs.get_origin(ekf_origin) && (ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M)) {
|
||||
if (ahrs.get_origin(ekf_origin) && ((ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M) || (labs(ekf_origin.alt - loc.alt) > EKF_ORIGIN_MAX_DIST_M))) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue