mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_Common: Location: move sanitize to be a method on location
This commit is contained in:
parent
81d51b1d1a
commit
fd294101ec
@ -238,5 +238,35 @@ float Location::longitude_scale() const
|
||||
return constrain_float(scale, 0.01f, 1.0f);
|
||||
}
|
||||
|
||||
/*
|
||||
* convert invalid waypoint with useful data. return true if location changed
|
||||
*/
|
||||
bool Location::sanitize(const Location &defaultLoc)
|
||||
{
|
||||
bool has_changed = false;
|
||||
// convert lat/lng=0 to mean current point
|
||||
if (lat == 0 && lng == 0) {
|
||||
lat = defaultLoc.lat;
|
||||
lng = defaultLoc.lng;
|
||||
has_changed = true;
|
||||
}
|
||||
|
||||
// convert relative alt=0 to mean current alt
|
||||
if (alt == 0 && relative_alt) {
|
||||
relative_alt = false;
|
||||
alt = defaultLoc.alt;
|
||||
has_changed = true;
|
||||
}
|
||||
|
||||
// limit lat/lng to appropriate ranges
|
||||
if (!check_latlng(lat, lng)) {
|
||||
lat = defaultLoc.lat;
|
||||
lng = defaultLoc.lng;
|
||||
has_changed = true;
|
||||
}
|
||||
|
||||
return has_changed;
|
||||
}
|
||||
|
||||
// make sure we know what size the Location object is:
|
||||
assert_storage_size<Location, 16> _assert_storage_size_Location;
|
||||
|
@ -85,6 +85,11 @@ public:
|
||||
|
||||
void zero(void);
|
||||
|
||||
/*
|
||||
* convert invalid waypoint with useful data. return true if location changed
|
||||
*/
|
||||
bool sanitize(const struct Location &defaultLoc);
|
||||
|
||||
private:
|
||||
static AP_Terrain *_terrain;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user