mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
GPS: fixed some stdint types
This commit is contained in:
parent
2f5a4cdc4a
commit
02ae5358d5
@ -55,7 +55,7 @@ AP_GPS_Auto::read(void)
|
||||
{
|
||||
GPS *gps;
|
||||
uint8_t i;
|
||||
unsigned long then;
|
||||
uint32_t then;
|
||||
|
||||
// Loop through possible baudrates trying to detect a GPS at one of them.
|
||||
//
|
||||
@ -96,7 +96,7 @@ AP_GPS_Auto::read(void)
|
||||
GPS *
|
||||
AP_GPS_Auto::_detect(void)
|
||||
{
|
||||
unsigned long then;
|
||||
uint32_t then;
|
||||
uint8_t fingerprint[4];
|
||||
uint8_t tries;
|
||||
uint16_t charcount;
|
||||
|
@ -184,10 +184,10 @@ int AP_GPS_NMEA::_from_hex(char a)
|
||||
return a - '0';
|
||||
}
|
||||
|
||||
unsigned long AP_GPS_NMEA::_parse_decimal()
|
||||
uint32_t AP_GPS_NMEA::_parse_decimal()
|
||||
{
|
||||
char *p = _term;
|
||||
unsigned long ret = 100UL * atol(p);
|
||||
uint32_t ret = 100UL * atol(p);
|
||||
while (isdigit(*p))
|
||||
++p;
|
||||
if (*p == '.') {
|
||||
@ -200,7 +200,7 @@ unsigned long AP_GPS_NMEA::_parse_decimal()
|
||||
return ret;
|
||||
}
|
||||
|
||||
unsigned long AP_GPS_NMEA::_parse_degrees()
|
||||
uint32_t AP_GPS_NMEA::_parse_degrees()
|
||||
{
|
||||
char *p, *q;
|
||||
uint8_t deg = 0, min = 0;
|
||||
|
@ -96,7 +96,7 @@ private:
|
||||
/// @returns The value expressed by the string in _term,
|
||||
/// multiplied by 100.
|
||||
///
|
||||
unsigned long _parse_decimal();
|
||||
uint32_t _parse_decimal();
|
||||
|
||||
/// Parses the current term as a NMEA-style degrees + minutes
|
||||
/// value with up to four decimal digits.
|
||||
@ -106,7 +106,7 @@ private:
|
||||
/// @returns The value expressed by the string in _term,
|
||||
/// multiplied by 10000.
|
||||
///
|
||||
unsigned long _parse_degrees();
|
||||
uint32_t _parse_degrees();
|
||||
|
||||
/// Processes the current term when it has been deemed to be
|
||||
/// complete.
|
||||
|
Loading…
Reference in New Issue
Block a user