ArduSub: 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:
Peter Barker 2024-04-09 17:41:12 +10:00 committed by Andrew Tridgell
parent 0c2636c191
commit 3443e1c12f
3 changed files with 2 additions and 14 deletions

View File

@ -425,7 +425,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);
float get_alt_rel() const WARN_IF_UNUSED;
float get_alt_msl() const WARN_IF_UNUSED;
void exit_mission();

View File

@ -73,12 +73,3 @@ bool Sub::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 Sub::far_from_EKF_origin(const Location& loc)
{
// check distance to EKF origin
Location ekf_origin;
return ahrs.get_origin(ekf_origin) && (ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M);
}

View File

@ -679,12 +679,10 @@ void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
// silently ignore this failure
}
} else {
if (!far_from_EKF_origin(cmd.content.location)) {
if (!set_home(cmd.content.location, false)) {
// silently ignore this failure
}
}
}
}
// do_roi - starts actions required by MAV_CMD_NAV_ROI