AP_GPS: make _parse_decimal_100() a static function

This allows to easily write tests for it as opposed to having to
construct the entire object.
This commit is contained in:
Lucas De Marchi 2016-05-19 10:10:49 -03:00
parent 7379d120e1
commit fc6dd97e61
2 changed files with 14 additions and 11 deletions

View File

@ -185,20 +185,22 @@ int16_t AP_GPS_NMEA::_from_hex(char a)
return a - '0'; return a - '0';
} }
int32_t AP_GPS_NMEA::_parse_decimal_100() int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
{ {
char *p = _term;
int32_t ret = 100UL * atol(p); int32_t ret = 100UL * atol(p);
int32_t sign = 1; int32_t sign = 1;
if (*p == '+') { if (*p == '+') {
++p; ++p;
} else if (*p == '-') { } else if (*p == '-') {
++p; ++p;
sign = -1; sign = -1;
} }
while (isdigit(*p)) { while (isdigit(*p)) {
++p; ++p;
} }
if (*p == '.') { if (*p == '.') {
if (isdigit(p[1])) { if (isdigit(p[1])) {
ret += sign * 10 * DIGIT_TO_VAL(p[1]); ret += sign * 10 * DIGIT_TO_VAL(p[1]);
@ -210,6 +212,7 @@ int32_t AP_GPS_NMEA::_parse_decimal_100()
} }
} }
} }
return ret; return ret;
} }
@ -390,14 +393,14 @@ bool AP_GPS_NMEA::_term_complete()
_new_satellite_count = atol(_term); _new_satellite_count = atol(_term);
break; break;
case _GPS_SENTENCE_GGA + 8: // HDOP (GGA) case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)
_new_hdop = _parse_decimal_100(); _new_hdop = (uint16_t)_parse_decimal_100(_term);
break; break;
// time and date // time and date
// //
case _GPS_SENTENCE_RMC + 1: // Time (RMC) case _GPS_SENTENCE_RMC + 1: // Time (RMC)
case _GPS_SENTENCE_GGA + 1: // Time (GGA) case _GPS_SENTENCE_GGA + 1: // Time (GGA)
_new_time = _parse_decimal_100(); _new_time = _parse_decimal_100(_term);
break; break;
case _GPS_SENTENCE_RMC + 9: // Date (GPRMC) case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)
_new_date = atol(_term); _new_date = atol(_term);
@ -424,18 +427,18 @@ bool AP_GPS_NMEA::_term_complete()
_new_longitude = -_new_longitude; _new_longitude = -_new_longitude;
break; break;
case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA) case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)
_new_altitude = _parse_decimal_100(); _new_altitude = _parse_decimal_100(_term);
break; break;
// course and speed // course and speed
// //
case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC) case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
case _GPS_SENTENCE_VTG + 5: // Speed (VTG) case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
_new_speed = (_parse_decimal_100() * 514) / 1000; // knots-> m/sec, approximiates * 0.514 _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514
break; break;
case _GPS_SENTENCE_RMC + 8: // Course (GPRMC) case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)
case _GPS_SENTENCE_VTG + 1: // Course (VTG) case _GPS_SENTENCE_VTG + 1: // Course (VTG)
_new_course = _parse_decimal_100(); _new_course = _parse_decimal_100(_term);
break; break;
} }
} }

View File

@ -85,13 +85,13 @@ private:
/// ///
int16_t _from_hex(char a); int16_t _from_hex(char a);
/// Parses the current term as a NMEA-style decimal number with /// Parses the @p as a NMEA-style decimal number with
/// up to two decimal digits. /// up to 3 decimal digits.
/// ///
/// @returns The value expressed by the string in _term, /// @returns The value expressed by the string in @p,
/// multiplied by 100. /// multiplied by 100.
/// ///
int32_t _parse_decimal_100(); static int32_t _parse_decimal_100(const char *p);
/// Parses the current term as a NMEA-style degrees + minutes /// Parses the current term as a NMEA-style degrees + minutes
/// value with up to four decimal digits. /// value with up to four decimal digits.