mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: Add same_loc_as function to Location
This commit is contained in:
parent
c445bb5f9e
commit
76e8407297
@ -110,6 +110,11 @@ public:
|
|||||||
// check if altitude matches.
|
// check if altitude matches.
|
||||||
bool same_alt_as(const Location &loc2) const;
|
bool same_alt_as(const Location &loc2) const;
|
||||||
|
|
||||||
|
// check if lat, lng, and alt match.
|
||||||
|
bool same_loc_as(const Location &loc2) const {
|
||||||
|
return same_latlon_as(loc2) && same_alt_as(loc2);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* convert invalid waypoint with useful data. return true if location changed
|
* convert invalid waypoint with useful data. return true if location changed
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user