AP_Common: move check_latlng to Location

This commit is contained in:
Pierre Kancir 2019-04-08 15:51:23 +02:00 committed by Tom Pittenger
parent 54bc960ca3
commit 29b2d7996b
2 changed files with 10 additions and 1 deletions

View File

@ -284,7 +284,7 @@ bool Location::sanitize(const Location &defaultLoc)
}
// limit lat/lng to appropriate ranges
if (!check_latlng(lat, lng)) {
if (!check_latlng()) {
lat = defaultLoc.lat;
lng = defaultLoc.lng;
has_changed = true;
@ -316,3 +316,9 @@ bool Location::same_latlon_as(const Location &loc2) const
{
return (lat == loc2.lat) && (lng == loc2.lng);
}
// return true when lat and lng are within range
bool Location::check_latlng() const
{
return check_lat(lat) && check_lng(lng);
}

View File

@ -102,6 +102,9 @@ public:
*/
bool sanitize(const struct Location &defaultLoc);
// return true when lat and lng are within range
bool check_latlng() const;
private:
static AP_Terrain *_terrain;
};