Tob1112 / ardupilot-mega

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

GPS_NMEA compatibility for higher precision messages #416

Open GoogleCodeExporter opened 9 years ago

GoogleCodeExporter commented 9 years ago
What steps will reproduce the problem?
1. Use a GPS receiver that reports higher precision or supports DGPS

What is the expected output? What do you see instead?
- Extra precision is ignored by decimal parser.

Please provide any additional information below.
- Can be resolved with modified _parse_decimal

--------------------------------------------------
////////Header
/// Parses the current term as a NMEA-style decimal number with
/// variable number of digits.
///
/// @param  numdec  The number of decimal places to evaluate
/// @param  p       String pointer. Allows use within _parse_degrees
///                 or other routines in subclass library.
/// @returns    The value expressed by the string in _term,
///     multiplied by 10 ^ numdec,
///             regardless of number of decimal places available
///
unsigned long   _parse_decimal(char *p, byte numdec);

--------------------------------------------------
//////// Example use
// parsing a single term
_new_hdop = _parse_decimal(_term, 2);

// parsing [D][D]Dmm.mmmmmm
min_e6 = _parse_decimal(q, 6);
return deg * 10000000UL + (min_e6 / 6); 

--------------------------------------------------
//////// Implementation
// Function to parse fixed/floating point numbers (numdec=number of decimals)
// If insufficient decimals are found, it still reaches the requested exponent
unsigned long AP_GPS_NMEA::_parse_decimal(char *p, byte numdec)
{
    unsigned long ret = 0;
    byte ndec = 0;

    while (ndec==0 || ndec <= numdec) {
        if (*p == '.'){
            ndec = 1;
        }
        else {
            if (!isdigit(*p)) {
                while (ndec++ <= numdec) {
                    ret *= 10;
                }
                return ret;
            }
            ret *= 10;
            ret += *p - '0';
            if (ndec > 0)
                ndec++;
        }
        p++;
    }
    return ret;
}

unsigned long AP_GPS_NMEA::_parse_degrees()
{
    char *p, *q;
    uint8_t deg = 0;
    unsigned long min_e6;

    // scan for decimal point or end of field
    for (p = _term; isdigit(*p); p++)
        ;
    q = _term;

    // convert degrees, leaving 2 digits for whole minutes
    while ((p - q) > 2) {
        if (deg)
            deg *= 10;
        deg += DIGIT_TO_VAL(*q++);
    }

    // parse minutes * 10e6
    min_e6 = _parse_decimal(q, 6);

    return deg * 10000000UL + (min_e6 / 6); // raise to 10e7, with minutes / 60
}

------------------------------------------
Note the attached file also contains the following fix  to NOT reject DGPS 
fixes:
case (_GPS_SENTENCE_GPRMC+2): 
   // validity (RMC) Autonomous | Differential | None | Estimated | Manual-input
_gps_data_good = (_term[0] == 'A') || (_term[0] == 'D');

Original issue reported on code.google.com by greg.nas...@gmail.com on 12 Sep 2011 at 12:06

Attachments:

GoogleCodeExporter commented 9 years ago
Sorry, I should probably have called this "enhancement". However, the 
Differential Fix is correcting a defect.

Original comment by greg.nas...@gmail.com on 13 Sep 2011 at 2:56

GoogleCodeExporter commented 9 years ago
I have a faster version of this code now.

Original comment by greg.nas...@gmail.com on 20 Sep 2011 at 1:54

GoogleCodeExporter commented 9 years ago
Greg: if you would still like to submit this code change, I can add you to the 
dev list so you can discuss it directly with the developers. Please just give 
me an email address that you'd like addded. 

Original comment by analogue...@gmail.com on 2 Jan 2012 at 9:20

GoogleCodeExporter commented 9 years ago
Am now on the dev list, and will look to deal with this shortly.

Original comment by greg.nas...@gmail.com on 4 Jan 2012 at 9:40

GoogleCodeExporter commented 9 years ago
Code now available on http://code.google.com/r/gregnashau-nmea-cts/
in master/libraries/AP_GPS

- supports variable length decimal strings
- supports requested decimal precision (old routine assumed fixed number of 
digits/places)
- recognises Differential fix as valid
- converts to (degrees x 1e7) without calling division in math library - is 
performance so tight we'd want to save 2 division ops per GPS position?

Original comment by greg.nas...@gmail.com on 17 Feb 2012 at 1:38