Browse Source

AP_Common: move check_latlng to Location

master
Pierre Kancir 6 years ago committed by Tom Pittenger
parent
commit
29b2d7996b
  1. 8
      libraries/AP_Common/Location.cpp
  2. 3
      libraries/AP_Common/Location.h

8
libraries/AP_Common/Location.cpp

@ -284,7 +284,7 @@ bool Location::sanitize(const Location &defaultLoc) @@ -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 @@ -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);
}

3
libraries/AP_Common/Location.h

@ -102,6 +102,9 @@ public: @@ -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;
};

Loading…
Cancel
Save