Owne / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

NMEA altitude error #277

Open GoogleCodeExporter opened 8 years ago

GoogleCodeExporter commented 8 years ago
What steps will reproduce the problem?
1. Use NMEA protocol
2. Go into CLI mode
3. Run `gps`, and then `rawgps`, view two different altitude values

What is the expected output? What do you see instead?

I expect to see about 26 to 29Meters in altitude for my location, and this is 
what the rawgps output lists, however the `gps` output lists anywhere from 260 
to 290 meters, as if it's removing the decimal point.

What version of the product are you using? On what operating system?

Latest version from the downloads tab, compiling and uploading via arduino on 
windows

Please provide any additional information below.

test] gps
Hit Enter to exit.

Lat:-36.8957138061 Lon:174.6611785888 Alt: 226m, #sats: 0
GPSERR: Checksum error!!

Lat:-36.8957138061 Lon:174.6611785888 Alt: 226m, #sats: 0
Lat:-36.8957138061 Lon:174.6611785888 Alt: 253m, #sats: 0
Lat:-36.8957138061 Lon:174.6611785888 Alt: 249m, #sats: 0
Lat:-36.8957138061 Lon:174.6611785888 Alt: 249m, #sats: 0
Lat:-36.8957138061 Lon:174.6611785888 Alt: 247m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 250m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 250m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 253m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 257m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 257m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 261m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 266m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 266m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 270m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 273m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 273m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 273m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 271m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 271m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 271m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 272m, #sats: 0
Lat:-36.8957176208 Lon:174.6611785888 Alt: 272m, #sats: 0
Lat:-36.8957214355 Lon:174.6611785888 Alt: 277m, #sats: 0
Lat:-36.8957252502 Lon:174.6611785888 Alt: 280m, #sats: 0
Lat:-36.8957252502 Lon:174.6611785888 Alt: 280m, #sats: 0
test] 
test] rawgps
Hit Enter to exit.

$GPGGA,002132.091,3653.7434,S,17439.6711,E,1,05,1.3,28.2,M,29.1,M,,0000*70
$GPGGA,002132.591,3653.7434,S,17439.6711,E,1,05,1.3 
$GPGGA,002135.091,3653.7434,S,17439.6710,E,1,05,1.3,31.5,M,29.1,M,,0000*79

$GPGGA,002135.591,3653.7435,S,17439.6709,E,1,05,1.3,31.3,M,29.1,M,,0000*73
$GPVTG,257.4,T,,M,000.0,N,000.0,K,A*09

$GPGGA,002136.091,3653.7435,S,17439.6709,E,1,05,1.3,31.1,M,29.1,M,,0000*77

$GPGGA,002136.591,3653.7436,S,17439.6708,E,1,05,1.3,30.9,M,29.1,M,,0000*79
$GPVTG,257.4,T,,M,000.0,N,000.0,K,A*09

$GPGGA,002137.091,3653.7436,S,17439.6708,E,1,05,1.3,30.9,M,29.1,M,,0000*7D

$GPGGA,002137.591,3653.7437,S,17439.6707,E,1,05,1.3,30.8,M,29.1,M,,0000*77
$GPVTG,257.4,T,,M,000.0,N,000.0,K,A*09

$GPGGA,002138.091,3653.7437,S,17439.6706,E,1,05,1.3,30.8,M,29.1,M,,0000*7C

test] 
test] 

Original issue reported on code.google.com by defy...@gmail.com on 10 Feb 2011 at 12:25

GoogleCodeExporter commented 8 years ago
I have tried this with a EM408 and Venus634 gps modules, both have the same 
result

Original comment by defy...@gmail.com on 10 Feb 2011 at 3:34

GoogleCodeExporter commented 8 years ago
The problem appears to be  that the printf statement on line 148 of test.pde is 
trying to format the number as an integer instead of a floating point.

Change line 148 of test.pde from: 

Serial.printf_P(PSTR(" Alt: %dm, #sats: %d\n"), GPS.altitude/100, GPS.num_sats);

to:

Serial.printf_P(PSTR(" Alt: %4.1fm, #sats: %d\n"), GPS.altitude/100, 
GPS.num_sats);

And tell me if that solves the problem.   (I don't have an APM or a GPS so I 
can't test it myself.)

Cheers.

Original comment by rvand...@gmail.com on 16 Feb 2011 at 2:27

GoogleCodeExporter commented 8 years ago
I currently don't have access to my ardupilot so I can't test, but would this 
imply that the error is only within the test section of the CLI?

I need to include that I get the exact same result when the telemetry is being 
sent down the telemetry com port, I get an altitude of roughly 250-300M when it 
should be less than 30.

Original comment by defy...@gmail.com on 23 Feb 2011 at 9:05

GoogleCodeExporter commented 8 years ago
OK, I looked at this again.  The REAL problem is on line 146 of 
AP_GPS_NMEA.cpp.  When the algorithm calls parsenumber() function the result is 
the altitude in decimeters instead of meters.

The original coder then multiplies by 100 to convert to millimeters, and stores 
the result in the GPS.altitude property.   The problem is that GPS.altitude is 
expecting centimeters (as defined in GPS.h) 

So change line 146 of AP_GPS_NMEA.cpp to read: 

altitude = parsenumber(parseptr, 1) * 10;   // altitude in decimeters * 10 = 
centimeters

and it should start working OK. 

Original comment by rvand...@gmail.com on 10 Mar 2011 at 6:56

GoogleCodeExporter commented 8 years ago
That is great, thank you for finding the issue, any chance this can be fixed 
perminantly in the next release?

Original comment by defy...@gmail.com on 14 Apr 2011 at 3:45

GoogleCodeExporter commented 8 years ago
It looks like the GPS libs have been completely revamped in the mainline.  The 
issue should be resolved if you download the latest.

Original comment by rvand...@gmail.com on 14 Apr 2011 at 12:04

GoogleCodeExporter commented 8 years ago
Current code may still be afflicted by GPS receivers providing different 
numbers of decimal places on some fields, due to the way _parse_decimal is 
coded.
Code attached to issue #416 is more flexible in handling precision variations 
in NMEA output.

Original comment by greg.nas...@gmail.com on 20 Sep 2011 at 2:16