mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Copter: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
62fa59238b
commit
08124faab4
@ -107,7 +107,7 @@ bool Copter::far_from_EKF_origin(const Location& loc)
|
||||
{
|
||||
// check distance to EKF origin
|
||||
const struct Location &ekf_origin = inertial_nav.get_origin();
|
||||
if (get_distance(ekf_origin, loc) > EKF_ORIGIN_MAX_DIST_M) {
|
||||
if (ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -14,7 +14,7 @@ void Copter::run_nav_updates(void)
|
||||
uint32_t Copter::home_distance()
|
||||
{
|
||||
if (position_ok()) {
|
||||
_home_distance = get_distance_cm(current_loc, ahrs.get_home());
|
||||
_home_distance = current_loc.get_distance(ahrs.get_home()) * 100;
|
||||
}
|
||||
return _home_distance;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user