Browse Source

Copter: AP_Arming: Added check for EKF origin altitude

c415-sdk
Arsh 4 years ago committed by Randy Mackay
parent
commit
3c83eecf78
  1. 2
      ArduCopter/commands.cpp

2
ArduCopter/commands.cpp

@ -107,7 +107,7 @@ bool Copter::far_from_EKF_origin(const Location& loc) @@ -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…
Cancel
Save