Browse Source

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.
master
JakobSt 11 years ago committed by Andrew Tridgell
parent
commit
986417067e
  1. 2
      libraries/AP_GPS/AP_GPS_NMEA.cpp

2
libraries/AP_GPS/AP_GPS_NMEA.cpp

@ -231,7 +231,7 @@ uint32_t AP_GPS_NMEA::_parse_degrees() @@ -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…
Cancel
Save