Skip to content

Commit

Permalink
Blimp: remove far_from_EKF_origin sanity checks
Browse files Browse the repository at this point in the history
some  flawed implementations, and the extreme-ardupilot project means these checks are no longer required
  • Loading branch information
peterbarker committed Apr 9, 2024
1 parent 6b90dc5 commit 8ff846d
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 20 deletions.
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;
}

0 comments on commit 8ff846d

Please sign in to comment.