AP_Math: use new check_latlng helper

This commit is contained in:
Tom Pittenger 2016-06-01 14:43:19 -07:00
parent ce9ecf9f3d
commit 7b4c503052
1 changed files with 1 additions and 1 deletions

View File

@ -177,7 +177,7 @@ bool location_sanitize(const struct Location &defaultLoc, struct Location &loc)
}
// limit lat/lng to appropriate ranges
if (abs(loc.lat) > 90 * 1e7 || abs(loc.lng) > 180 * 1e7) {
if (!check_latlng(loc)) {
loc.lat = defaultLoc.lat;
loc.lng = defaultLoc.lng;
has_changed = true;