mirror of https://github.com/ArduPilot/ardupilot
Fix MTK lat/lon scaling.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@414 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
63d1cf06c1
commit
1dd4bc9080
|
@ -127,8 +127,8 @@ AP_GPS_MTK::parse_gps(void)
|
|||
switch(id){
|
||||
//Checking the UBX ID
|
||||
case 0x05: // ID Custom
|
||||
latitude = _swapl(&buffer[0]);
|
||||
longitude = _swapl(&buffer[4]);
|
||||
latitude = _swapl(&buffer[0]) * 10;
|
||||
longitude = _swapl(&buffer[4]) * 10;
|
||||
altitude = _swapl(&buffer[8]);
|
||||
speed_3d = ground_speed = _swapl(&buffer[12]);
|
||||
ground_course = _swapl(&buffer[16]) / 10000;
|
||||
|
|
|
@ -42,7 +42,7 @@ void loop()
|
|||
Serial.print(" GSP:");
|
||||
Serial.print(gps.ground_speed / 100.0);
|
||||
Serial.print(" COG:");
|
||||
Serial.print(gps.ground_course / 100, DEC);
|
||||
Serial.print(gps.ground_course / 100.0, DEC);
|
||||
Serial.print(" SAT:");
|
||||
Serial.print(gps.num_sats, DEC);
|
||||
Serial.print(" FIX:");
|
||||
|
|
Loading…
Reference in New Issue