mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Common: clarify Location::get_distance is horizontal only
This commit is contained in:
parent
da961948db
commit
23ad8b23ac
@ -236,7 +236,7 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const
|
||||
return true;
|
||||
}
|
||||
|
||||
// return distance in meters between two locations
|
||||
// return horizontal distance in meters between two locations
|
||||
ftype Location::get_distance(const struct Location &loc2) const
|
||||
{
|
||||
ftype dlat = (ftype)(loc2.lat - lat);
|
||||
|
@ -56,7 +56,7 @@ public:
|
||||
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const WARN_IF_UNUSED;
|
||||
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const WARN_IF_UNUSED;
|
||||
|
||||
// return distance in meters between two locations
|
||||
// return horizontal distance in meters between two locations
|
||||
ftype get_distance(const struct Location &loc2) const;
|
||||
|
||||
// return the altitude difference in meters taking into account alt frame.
|
||||
|
Loading…
Reference in New Issue
Block a user