diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index d114efc3e2..6e2ab5c9d2 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -112,7 +112,7 @@ void AP_NMEA_Output::update() // format time string char tstring[10]; - snprintf(tstring, sizeof(tstring), "%02u%02u%05.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); + hal.util->snprintf(tstring, sizeof(tstring), "%02u%02u%05.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); Location loc; const auto &gps = AP::gps(); @@ -131,7 +131,7 @@ void AP_NMEA_Output::update() char lat_string[13]; double deg = fabs(loc.lat * 1.0e-7f); double min_dec = ((fabs(loc.lat) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; - snprintf(lat_string, + hal.util->snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c", (unsigned) deg, @@ -142,7 +142,7 @@ void AP_NMEA_Output::update() char lng_string[14]; deg = fabs(loc.lng * 1.0e-7f); min_dec = ((fabs(loc.lng) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; - snprintf(lng_string, + hal.util->snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c", (unsigned) deg, @@ -208,7 +208,7 @@ void AP_NMEA_Output::update() lng_string, fix_quality, gps.num_sats(), - gps.get_hdop(), + gps.get_hdop()*0.01, loc.alt * 0.01f); space_required += gga_length; @@ -219,7 +219,7 @@ void AP_NMEA_Output::update() if ((_message_enable_bitmask.get() & static_cast(Enabled_Messages::GPRMC)) != 0) { // format date string char dstring[7]; - snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); + hal.util->snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); // get speed #if AP_AHRS_ENABLED