mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_GPS: Improved accuracy of NMEA driver
The conversion of ret (32bit-integer) to float reduced accuracy to ~9cm or ~22cm. Now it's ~1cm.
This commit is contained in:
parent
b3d20bb8aa
commit
986417067e
@ -231,7 +231,7 @@ uint32_t AP_GPS_NMEA::_parse_degrees()
|
||||
}
|
||||
ret = (deg * (int32_t)10000000UL);
|
||||
ret += (min * (int32_t)10000000UL / 60);
|
||||
ret += frac_min * (1.0e7 / 60.0f);
|
||||
ret += (int32_t) (frac_min * (1.0e7 / 60.0f));
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user