Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove "far_from_EKF_origin" sanity checks #26727

Merged
merged 3 commits into from
Apr 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 0 additions & 12 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -495,18 +495,6 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
}
}

// check if home is too far from EKF origin
if (copter.far_from_EKF_origin(ahrs.get_home())) {
check_failed(display_failure, "Home too far from EKF origin");
return false;
}

// check if vehicle is too far from EKF origin
if (copter.far_from_EKF_origin(copter.current_loc)) {
check_failed(display_failure, "Vehicle too far from EKF origin");
return false;
}

// if we got here all must be ok
return true;
}
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -741,7 +741,6 @@ class Copter : public AP_Vehicle {
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);

// compassmot.cpp
MAV_RESULT mavlink_compassmot(const GCS_MAVLINK &gcs_chan);
Expand Down
21 changes: 0 additions & 21 deletions ArduCopter/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,11 +63,6 @@ bool Copter::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;
Expand All @@ -81,19 +76,3 @@ bool Copter::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 Copter::far_from_EKF_origin(const Location& loc)
{
// check distance to EKF origin
Location ekf_origin;
if (ahrs.get_origin(ekf_origin)) {
if (labs(ekf_origin.alt - loc.alt)*0.01 > EKF_ORIGIN_MAX_ALT_KM*1000.0) {
return true;
}
}

// close enough to origin
return false;
}
1 change: 0 additions & 1 deletion ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,6 @@ class Sub : public AP_Vehicle {
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();
Expand Down
9 changes: 0 additions & 9 deletions ArduSub/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
6 changes: 2 additions & 4 deletions ArduSub/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
}
}
Expand Down
1 change: 0 additions & 1 deletion Blimp/Blimp.h
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,6 @@ class Blimp : public AP_Vehicle
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();
Expand Down
19 changes: 0 additions & 19 deletions Blimp/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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