Copter: removed max home distance

after discussion with Randy we agreed to just remove this check now we
are numerically stable at long distances
This commit is contained in:
Andrew Tridgell 2021-07-12 16:50:53 +10:00
parent 7550368fc7
commit bd84ed126e
2 changed files with 0 additions and 6 deletions

View File

@ -108,9 +108,6 @@ bool Copter::far_from_EKF_origin(const Location& loc)
// check distance to EKF origin
Location ekf_origin;
if (ahrs.get_origin(ekf_origin)) {
if ((ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_KM*1000.0)) {
return true;
}
if (labs(ekf_origin.alt - loc.alt)*0.01 > EKF_ORIGIN_MAX_ALT_KM*1000.0) {
return true;
}

View File

@ -168,9 +168,6 @@
# define FS_EKF_THRESHOLD_DEFAULT 0.8f // EKF failsafe's default compass and velocity variance threshold above which the EKF failsafe will be triggered
#endif
#ifndef EKF_ORIGIN_MAX_DIST_KM
# define EKF_ORIGIN_MAX_DIST_KM 250 // EKF origin and home must be within 250km horizontally
#endif
#ifndef EKF_ORIGIN_MAX_ALT_KM
# define EKF_ORIGIN_MAX_ALT_KM 50 // EKF origin and home must be within 50km vertically
#endif