Skip to content
Snippets Groups Projects
Commit 84ed2141 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

AP_Math: fixed float rounding in location_offset()

this prevents rounding of positions in the rover code
parent 3e24ff1b
No related branches found
No related tags found
No related merge requests found
...@@ -133,8 +133,8 @@ void location_update(struct Location &loc, float bearing, float distance) ...@@ -133,8 +133,8 @@ void location_update(struct Location &loc, float bearing, float distance)
void location_offset(struct Location &loc, float ofs_north, float ofs_east) void location_offset(struct Location &loc, float ofs_north, float ofs_east)
{ {
if (ofs_north != 0 || ofs_east != 0) { if (ofs_north != 0 || ofs_east != 0) {
float dlat = ofs_north * LOCATION_SCALING_FACTOR_INV; int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
float dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc); int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc);
loc.lat += dlat; loc.lat += dlat;
loc.lng += dlng; loc.lng += dlng;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment