AP_Common: remove is-zero checks for Location::offset

Only one call in 160 actually passes these in as zeroes, so doing the
checks vastly outweighs the benefits of not doing the maths

We do call this a lot when doing terrain checks.
This commit is contained in:
Peter Barker 2019-11-06 11:56:23 +11:00 committed by Andrew Tridgell
parent d18432adaa
commit 6c0b4206c5

View File

@ -245,13 +245,10 @@ Vector3f Location::get_distance_NED(const Location &loc2) const
// extrapolate latitude/longitude given distances (in meters) north and east
void Location::offset(float ofs_north, float ofs_east)
{
// use is_equal() because is_zero() is a local class conflict and is_zero() in AP_Math does not belong to a class
if (!is_equal(ofs_north, 0.0f) || !is_equal(ofs_east, 0.0f)) {
int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale();
lat += dlat;
lng += dlng;
}
const int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
const int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale();
lat += dlat;
lng += dlng;
}
/*