GPS units that don't have 2 digits after decimal on heading and alt would cause serious math problem.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@807 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
paulbmather@gmail.com 2010-11-08 19:21:42 +00:00
parent 7dd853642c
commit bd205a48e8
1 changed files with 2 additions and 2 deletions

View File

@ -170,14 +170,14 @@ AP_GPS_NMEA::parse_nmea_gps(void)
valid_read = true;
new_data = true; // New GPS Data
parseptr = strchr(buffer, ',')+1;
ground_course = parsenumber(parseptr, 2); // Ground course in degrees * 100
ground_course = parsenumber(parseptr, 1) * 10; // Ground course in degrees * 100
parseptr = strchr(parseptr, ',')+1;
parseptr = strchr(parseptr, ',')+1;
parseptr = strchr(parseptr, ',')+1;
parseptr = strchr(parseptr, ',')+1;
parseptr = strchr(parseptr, ',')+1;
parseptr = strchr(parseptr, ',')+1;
ground_speed = parsenumber(parseptr, 2) * 10 / 36; // Convert Km / h to m / s ( * 100)
ground_speed = parsenumber(parseptr, 1) * 100 / 36; // Convert Km / h to m / s ( * 100)
//GPS_line = true;
} else {
_error("GPSERR: Checksum error!!\n");