Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

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

Merged
merged 1 commit into from
Nov 18, 2019
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 4 additions & 7 deletions libraries/AP_Common/Location.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

/*
Expand Down