mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Math: move locations_are_same to Location and rename to same_latlon_as
This commit is contained in:
parent
a700b647db
commit
b10e75f4e1
@ -308,3 +308,11 @@ int32_t Location::get_bearing_to(const struct Location &loc2) const
|
|||||||
}
|
}
|
||||||
return bearing;
|
return bearing;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return true if lat and lng match. Ignores altitude and options
|
||||||
|
*/
|
||||||
|
bool Location::same_latlon_as(const Location &loc2) const
|
||||||
|
{
|
||||||
|
return (lat == loc2.lat) && (lng == loc2.lng);
|
||||||
|
}
|
||||||
|
@ -94,6 +94,9 @@ public:
|
|||||||
// return bearing in centi-degrees from location to loc2
|
// return bearing in centi-degrees from location to loc2
|
||||||
int32_t get_bearing_to(const struct Location &loc2) const;
|
int32_t get_bearing_to(const struct Location &loc2) const;
|
||||||
|
|
||||||
|
// check if lat and lng match. Ignore altitude and options
|
||||||
|
bool same_latlon_as(const Location &loc2) const;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* convert invalid waypoint with useful data. return true if location changed
|
* convert invalid waypoint with useful data. return true if location changed
|
||||||
*/
|
*/
|
||||||
|
@ -88,12 +88,6 @@ Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location
|
|||||||
(loc1.alt - loc2.alt) * 0.01f);
|
(loc1.alt - loc2.alt) * 0.01f);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
return true if lat and lng match. Ignores altitude and options
|
|
||||||
*/
|
|
||||||
bool locations_are_same(const struct Location &loc1, const struct Location &loc2) {
|
|
||||||
return (loc1.lat == loc2.lat) && (loc1.lng == loc2.lng);
|
|
||||||
}
|
|
||||||
|
|
||||||
// return true when lat and lng are within range
|
// return true when lat and lng are within range
|
||||||
bool check_lat(float lat)
|
bool check_lat(float lat)
|
||||||
|
@ -48,10 +48,6 @@ float location_path_proportion(const struct Location &location,
|
|||||||
*/
|
*/
|
||||||
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2);
|
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2);
|
||||||
|
|
||||||
/*
|
|
||||||
* check if lat and lng match. Ignore altitude and options
|
|
||||||
*/
|
|
||||||
bool locations_are_same(const struct Location &loc1, const struct Location &loc2);
|
|
||||||
|
|
||||||
// Converts from WGS84 geodetic coordinates (lat, lon, height)
|
// Converts from WGS84 geodetic coordinates (lat, lon, height)
|
||||||
// into WGS84 Earth Centered, Earth Fixed (ECEF) coordinates
|
// into WGS84 Earth Centered, Earth Fixed (ECEF) coordinates
|
||||||
|
Loading…
Reference in New Issue
Block a user