mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Math: fixed float rounding in location_offset()
this prevents rounding of positions in the rover code
This commit is contained in:
parent
3e24ff1b07
commit
84ed2141a0
@ -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)
|
||||
{
|
||||
if (ofs_north != 0 || ofs_east != 0) {
|
||||
float dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
|
||||
float dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc);
|
||||
int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
|
||||
int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc);
|
||||
loc.lat += dlat;
|
||||
loc.lng += dlng;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user