50 #define DIGIT_TO_VAL(_x) (_x - '0') 51 #define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x)) 69 static FILE *logf =
nullptr;
70 if (logf ==
nullptr) {
71 logf =
fopen(NMEA_LOG_PATH,
"wb");
73 if (logf !=
nullptr) {
86 bool valid_sentence =
false;
102 return valid_sentence;
110 return valid_sentence;
119 return valid_sentence;
127 if (a >=
'A' && a <=
'F')
129 else if (a >=
'a' && a <=
'f')
137 char *endptr =
nullptr;
138 long ret = 100 * strtol(p, &endptr, 10);
139 int sign = ret < 0 ? -1 : 1;
141 if (ret >= (
long)INT32_MAX) {
144 if (ret <= (
long)INT32_MIN) {
147 if (endptr ==
nullptr || *endptr !=
'.') {
151 if (isdigit(endptr[1])) {
153 if (isdigit(endptr[2])) {
155 if (isdigit(endptr[3])) {
169 uint8_t deg = 0, min = 0;
174 for (p =
_term; *p && isdigit(*p); p++)
179 while ((p - q) > 2 && *q) {
186 while (p > q && *q) {
195 float frac_scale = 0.1f;
196 while (*q && isdigit(*q)) {
202 ret = (deg * (int32_t)10000000UL);
203 ret += (min * (int32_t)10000000UL / 60);
204 ret += (int32_t) (frac_min * (1.0e7f / 60.0
f));
328 const char *term_type = &
_term[2];
329 if (strcmp(term_type,
"RMC") == 0) {
331 }
else if (strcmp(term_type,
"GGA") == 0) {
333 }
else if (strcmp(term_type,
"VTG") == 0) {
423 switch (state.
step) {
int32_t _new_time
time parsed from a term
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
uint8_t _new_quality_indicator
GPS quality indicator parsed from a term.
GPS_Status status
driver fix status
bool _gps_data_good
set when the sentence indicates data is good
uint16_t _new_hdop
HDOP parsed from a term.
static bool _detect(struct NMEA_detect_state &state, uint8_t data)
int32_t lat
param 3 - Latitude * 10**7
Receiving valid messages and 3D RTK Fixed.
char _term[15]
buffer for the current term within the current sentence
uint8_t _new_satellite_count
satellite count parsed from a term
float wrap_360(const T angle, float unit_mod)
bool _have_new_message(void)
return true if we have a new set of NMEA messages
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Receiving valid messages and 3D lock with differential improvements.
uint8_t _parity
NMEA message checksum accumulator.
Receiving valid messages and 3D RTK Float.
uint32_t _parse_degrees()
AP_GPS::GPS_State & state
public state for this instance
int32_t _new_latitude
latitude parsed from a term
int32_t _new_speed
speed parsed from a term
uint8_t _term_number
term index within the current sentence
Common definitions and utility routines for the ArduPilot libraries.
int32_t _new_longitude
longitude parsed from a term
virtual uint32_t available()=0
Location location
last fix location
int32_t lng
param 4 - Longitude * 10**7
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
void fill_3d_velocity(void)
int16_t _from_hex(char a)
Receiving valid GPS messages but no lock.
uint8_t _term_offset
character offset with the term being received
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
int32_t _new_date
date parsed from a term
static int32_t _parse_decimal_100(const char *p)
AP_HAL::UARTDriver * port
UART we are attached to.
size_t fwrite(const void *ptr, size_t size, size_t nmemb, FILE *stream)
POSIX write nmemb elements from buf, size bytes each, to the stream fd.
float ground_speed
ground speed in m/sec
Receiving valid messages and 3D lock.
uint8_t _sentence_type
the sentence type currently being processed
AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
int32_t _new_altitude
altitude parsed from a term
uint16_t hdop
horizontal dilution of precision in cm
bool _is_checksum_term
current term is the checksum
uint8_t num_sats
Number of visible satellites.
int32_t _new_course
course parsed from a term
float ground_course
ground course in degrees