mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
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:
parent
0c2636c191
commit
3443e1c12f
@ -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();
|
||||
|
@ -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);
|
||||
}
|
||||
|
@ -679,10 +679,8 @@ 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
|
||||
}
|
||||
if (!set_home(cmd.content.location, false)) {
|
||||
// silently ignore this failure
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user