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:
JakobSt 2014-01-12 19:51:50 +01:00 committed by Andrew Tridgell
parent b3d20bb8aa
commit 986417067e

View File

@ -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;
}