mirror of https://github.com/ArduPilot/ardupilot
Blimp: remove far_from_EKF_origin sanity checks
some flawed implementations, and the extreme-ardupilot project means these checks are no longer required
This commit is contained in:
parent
3443e1c12f
commit
335db007e9
|
@ -312,7 +312,6 @@ private:
|
|||
void set_home_to_current_location_inflight();
|
||||
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
||||
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
||||
bool far_from_EKF_origin(const Location& loc);
|
||||
|
||||
// ekf_check.cpp
|
||||
void ekf_check();
|
||||
|
|
|
@ -58,11 +58,6 @@ bool Blimp::set_home(const Location& loc, bool lock)
|
|||
return false;
|
||||
}
|
||||
|
||||
// check home is close to EKF origin
|
||||
if (far_from_EKF_origin(loc)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// set ahrs home (used for RTL)
|
||||
if (!ahrs.set_home(loc)) {
|
||||
return false;
|
||||
|
@ -76,17 +71,3 @@ bool Blimp::set_home(const Location& loc, bool lock)
|
|||
// return success
|
||||
return true;
|
||||
}
|
||||
|
||||
// far_from_EKF_origin - checks if a location is too far from the EKF origin
|
||||
// returns true if too far
|
||||
bool Blimp::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) || (labs(ekf_origin.alt - loc.alt) > EKF_ORIGIN_MAX_DIST_M))) {
|
||||
return true;
|
||||
}
|
||||
|
||||
// close enough to origin
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue