Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NMEA_Output.cpp: Fix conversion precision issue: #21790

Merged
merged 1 commit into from Oct 6, 2022
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
12 changes: 8 additions & 4 deletions libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
Expand Up @@ -16,6 +16,7 @@
Author: Francisco Ferreira (some code is copied from sitl_gps.cpp)

*/
#define ALLOW_DOUBLE_MATH_FUNCTIONS

#include "AP_NMEA_Output.h"

Expand Down Expand Up @@ -101,22 +102,25 @@ void AP_NMEA_Output::update()

// format latitude
char lat_string[13];
float deg = fabsf(loc.lat * 1.0e-7f);
double deg = fabs(loc.lat * 1.0e-7f);
double min_dec = ((fabs(loc.lat) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f;
Davidsastresas marked this conversation as resolved.
Show resolved Hide resolved
snprintf(lat_string,
sizeof(lat_string),
"%02u%08.5f,%c",
Davidsastresas marked this conversation as resolved.
Show resolved Hide resolved
(unsigned) deg,
double((deg - int(deg)) * 60),
min_dec,
loc.lat < 0 ? 'S' : 'N');


// format longitude
char lng_string[14];
deg = fabsf(loc.lng * 1.0e-7f);
deg = fabs(loc.lng * 1.0e-7f);
min_dec = ((fabs(loc.lng) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f;
Davidsastresas marked this conversation as resolved.
Show resolved Hide resolved
snprintf(lng_string,
sizeof(lng_string),
"%03u%08.5f,%c",
(unsigned) deg,
double((deg - int(deg)) * 60),
min_dec,
loc.lng < 0 ? 'W' : 'E');

// format GGA message
Expand Down