mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Sub: 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
f430fd14f6
commit
3fd5e05601
@ -99,5 +99,5 @@ bool Sub::far_from_EKF_origin(const Location& loc)
|
||||
{
|
||||
// check distance to EKF origin
|
||||
const struct Location &ekf_origin = inertial_nav.get_origin();
|
||||
return (get_distance(ekf_origin, loc) > EKF_ORIGIN_MAX_DIST_M);
|
||||
return (ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user