Skip to content

Commit

Permalink
ArduCopter: 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 5e5fde7 commit 2f71a40
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 34 deletions.
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;
}

0 comments on commit 2f71a40

Please sign in to comment.