CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS_NMEA.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
//
17
// NMEA parser, adapted by Michael Smith from TinyGPS v9:
18
//
19
// TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
20
// Copyright (C) 2008-9 Mikal Hart
21
// All rights reserved.
22
//
23
24
/// @file AP_GPS_NMEA.cpp
25
/// @brief NMEA protocol parser
26
///
27
/// This is a lightweight NMEA parser, derived originally from the
28
/// TinyGPS parser by Mikal Hart.
29
///
30
31
#include <AP_Common/AP_Common.h>
32
#include <AP_Common/NMEA.h>
33
#include <GCS_MAVLink/GCS.h>
34
#include <AP_Logger/AP_Logger.h>
35
36
#include <ctype.h>
37
#include <stdint.h>
38
#include <stdlib.h>
39
#include <stdio.h>
40
41
#include "AP_GPS_NMEA.h"
42
43
#if AP_GPS_NMEA_ENABLED
44
extern const AP_HAL::HAL& hal;
45
46
#ifndef AP_GPS_NMEA_CONFIG_PERIOD_MS
47
// how often we send board specific config commands
48
#define AP_GPS_NMEA_CONFIG_PERIOD_MS 15000U
49
#endif
50
51
// a quiet nan for invalid values
52
#define QNAN nanf("GPS")
53
54
// Convenience macros //////////////////////////////////////////////////////////
55
//
56
#define DIGIT_TO_VAL(_x) (_x - '0')
57
#define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x))
58
59
bool AP_GPS_NMEA::read(void)
60
{
61
int16_t numc;
62
bool parsed = false;
63
64
send_config();
65
66
numc = port->available();
67
while (numc--) {
68
char c = port->read();
69
#if AP_GPS_DEBUG_LOGGING_ENABLED
70
log_data((const uint8_t *)&c, 1);
71
#endif
72
if (_decode(c)) {
73
parsed = true;
74
}
75
}
76
return parsed;
77
}
78
79
/*
80
decode one character, return true if we have successfully completed a sentence, false otherwise
81
*/
82
bool AP_GPS_NMEA::_decode(char c)
83
{
84
_sentence_length++;
85
86
switch (c) {
87
case ';':
88
// header separator for unicore
89
if (!_is_unicore) {
90
return false;
91
}
92
FALLTHROUGH;
93
case ',': // term terminators
94
_parity ^= c;
95
if (_is_unicore) {
96
_crc32 = crc_crc32(_crc32, (const uint8_t *)&c, 1);
97
}
98
FALLTHROUGH;
99
case '\r':
100
case '\n':
101
case '*': {
102
if (_sentence_done) {
103
return false;
104
}
105
bool valid_sentence = false;
106
if (_term_offset < sizeof(_term)) {
107
_term[_term_offset] = 0;
108
valid_sentence = _term_complete();
109
}
110
++_term_number;
111
_term_offset = 0;
112
_is_checksum_term = c == '*';
113
return valid_sentence;
114
}
115
116
case '$': // sentence begin
117
case '#': // unicore message begin
118
_is_unicore = (c == '#');
119
_term_number = _term_offset = 0;
120
_parity = 0;
121
_crc32 = 0;
122
_sentence_type = _GPS_SENTENCE_OTHER;
123
_is_checksum_term = false;
124
_sentence_length = 1;
125
_sentence_done = false;
126
_new_gps_yaw = QNAN;
127
return false;
128
}
129
130
// ordinary characters
131
if (_term_offset < sizeof(_term) - 1)
132
_term[_term_offset++] = c;
133
if (!_is_checksum_term) {
134
_parity ^= c;
135
if (_is_unicore) {
136
_crc32 = crc_crc32(_crc32, (const uint8_t *)&c, 1);
137
}
138
}
139
140
return false;
141
}
142
143
int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
144
{
145
char *endptr = nullptr;
146
long ret = 100 * strtol(p, &endptr, 10);
147
int sign = ret < 0 ? -1 : 1;
148
149
if (ret >= (long)INT32_MAX) {
150
return INT32_MAX;
151
}
152
if (ret <= (long)INT32_MIN) {
153
return INT32_MIN;
154
}
155
if (endptr == nullptr || *endptr != '.') {
156
return ret;
157
}
158
159
if (isdigit(endptr[1])) {
160
ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);
161
if (isdigit(endptr[2])) {
162
ret += sign * DIGIT_TO_VAL(endptr[2]);
163
if (isdigit(endptr[3])) {
164
ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);
165
}
166
}
167
}
168
return ret;
169
}
170
171
/*
172
parse a NMEA latitude/longitude degree value. The result is in degrees*1e7
173
*/
174
uint32_t AP_GPS_NMEA::_parse_degrees()
175
{
176
char *p, *q;
177
uint8_t deg = 0, min = 0;
178
float frac_min = 0;
179
int32_t ret = 0;
180
181
// scan for decimal point or end of field
182
for (p = _term; *p && isdigit(*p); p++)
183
;
184
q = _term;
185
186
// convert degrees
187
while ((p - q) > 2 && *q) {
188
if (deg)
189
deg *= 10;
190
deg += DIGIT_TO_VAL(*q++);
191
}
192
193
// convert minutes
194
while (p > q && *q) {
195
if (min)
196
min *= 10;
197
min += DIGIT_TO_VAL(*q++);
198
}
199
200
// convert fractional minutes
201
if (*p == '.') {
202
q = p + 1;
203
float frac_scale = 0.1f;
204
while (*q && isdigit(*q)) {
205
frac_min += DIGIT_TO_VAL(*q) * frac_scale;
206
q++;
207
frac_scale *= 0.1f;
208
}
209
}
210
ret = (deg * (int32_t)10000000UL);
211
ret += (min * (int32_t)10000000UL / 60);
212
ret += (int32_t) (frac_min * (1.0e7f / 60.0f));
213
return ret;
214
}
215
216
/*
217
see if we have a new set of NMEA messages
218
*/
219
bool AP_GPS_NMEA::_have_new_message()
220
{
221
if (_last_RMC_ms == 0 ||
222
_last_GGA_ms == 0) {
223
return false;
224
}
225
uint32_t now = AP_HAL::millis();
226
if (now - _last_RMC_ms > 150 ||
227
now - _last_GGA_ms > 150) {
228
return false;
229
}
230
if (_last_VTG_ms != 0 &&
231
now - _last_VTG_ms > 150) {
232
return false;
233
}
234
235
/*
236
if we have seen a message with 3D velocity data messages then
237
wait for them again. This is important as the
238
have_vertical_velocity field will be overwritten by
239
fill_3d_velocity()
240
*/
241
if (_last_vvelocity_ms != 0 &&
242
now - _last_vvelocity_ms > 150 &&
243
now - _last_vvelocity_ms < 1000) {
244
// waiting on a message with velocity
245
return false;
246
}
247
if (_last_vaccuracy_ms != 0 &&
248
now - _last_vaccuracy_ms > 150 &&
249
now - _last_vaccuracy_ms < 1000) {
250
// waiting on a message with velocity accuracy
251
return false;
252
}
253
254
// prevent these messages being used again
255
if (_last_VTG_ms != 0) {
256
_last_VTG_ms = 1;
257
}
258
259
if (now - _last_yaw_ms > 300) {
260
// we have lost GPS yaw
261
state.have_gps_yaw = false;
262
}
263
264
if (now - _last_KSXT_pos_ms > 500) {
265
// we have lost KSXT
266
_last_KSXT_pos_ms = 0;
267
}
268
269
#if AP_GPS_NMEA_UNICORE_ENABLED
270
if (now - _last_AGRICA_ms > 500) {
271
if (_last_AGRICA_ms != 0) {
272
// we have lost AGRICA
273
state.have_gps_yaw = false;
274
state.have_vertical_velocity = false;
275
state.have_speed_accuracy = false;
276
state.have_horizontal_accuracy = false;
277
state.have_vertical_accuracy = false;
278
state.have_undulation = false;
279
_last_AGRICA_ms = 0;
280
}
281
}
282
#endif // AP_GPS_NMEA_UNICORE_ENABLED
283
284
_last_fix_ms = now;
285
286
_last_GGA_ms = 1;
287
_last_RMC_ms = 1;
288
return true;
289
}
290
291
// Processes a just-completed term
292
// Returns true if new sentence has just passed checksum test and is validated
293
bool AP_GPS_NMEA::_term_complete()
294
{
295
// handle the last term in a message
296
if (_is_checksum_term) {
297
_sentence_done = true;
298
const uint32_t crc = strtoul(_term, nullptr, 16);
299
const bool crc_ok = _is_unicore? (_crc32 == crc) : (_parity == crc);
300
if (crc_ok) {
301
uint32_t now = AP_HAL::millis();
302
switch (_sentence_type) {
303
case _GPS_SENTENCE_RMC:
304
_last_RMC_ms = now;
305
//time = _new_time;
306
//date = _new_date;
307
if (_last_KSXT_pos_ms == 0 && _last_AGRICA_ms == 0) {
308
state.location.lat = _new_latitude;
309
state.location.lng = _new_longitude;
310
}
311
if (_last_3D_velocity_ms == 0 ||
312
now - _last_3D_velocity_ms > 1000) {
313
state.ground_speed = _new_speed*0.01f;
314
state.ground_course = wrap_360(_new_course*0.01f);
315
}
316
if (state.status >= AP_GPS::GPS_OK_FIX_3D) {
317
make_gps_time(_new_date, _new_time * 10);
318
if (_last_AGRICA_ms != 0) {
319
state.time_week_ms = _last_itow_ms;
320
}
321
}
322
set_uart_timestamp(_sentence_length);
323
state.last_gps_time_ms = now;
324
if (_last_vvelocity_ms == 0 ||
325
now - _last_vvelocity_ms > 1000) {
326
fill_3d_velocity();
327
}
328
break;
329
case _GPS_SENTENCE_GGA:
330
_last_GGA_ms = now;
331
if (_last_KSXT_pos_ms == 0 && _last_AGRICA_ms == 0) {
332
set_alt_amsl_cm(state, _new_altitude);
333
state.location.lat = _new_latitude;
334
state.location.lng = _new_longitude;
335
}
336
state.num_sats = _new_satellite_count;
337
state.hdop = _new_hdop;
338
switch(_new_quality_indicator) {
339
case 0: // Fix not available or invalid
340
state.status = AP_GPS::NO_FIX;
341
break;
342
case 1: // GPS SPS Mode, fix valid
343
state.status = AP_GPS::GPS_OK_FIX_3D;
344
break;
345
case 2: // Differential GPS, SPS Mode, fix valid
346
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
347
break;
348
case 3: // GPS PPS Mode, fix valid
349
state.status = AP_GPS::GPS_OK_FIX_3D;
350
break;
351
case 4: // Real Time Kinematic. System used in RTK mode with fixed integers
352
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
353
break;
354
case 5: // Float RTK. Satellite system used in RTK mode, floating integers
355
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
356
break;
357
case 6: // Estimated (dead reckoning) Mode
358
state.status = AP_GPS::NO_FIX;
359
break;
360
default://to maintain compatibility with MAV_GPS_INPUT and others
361
state.status = AP_GPS::GPS_OK_FIX_3D;
362
break;
363
}
364
break;
365
case _GPS_SENTENCE_VTG:
366
_last_VTG_ms = now;
367
if (_last_3D_velocity_ms == 0 ||
368
now - _last_3D_velocity_ms > 1000) {
369
state.ground_speed = _new_speed*0.01f;
370
state.ground_course = wrap_360(_new_course*0.01f);
371
if (_last_vvelocity_ms == 0 ||
372
now - _last_vvelocity_ms > 1000) {
373
fill_3d_velocity();
374
}
375
}
376
// VTG has no fix indicator, can't change fix status
377
break;
378
case _GPS_SENTENCE_HDT:
379
case _GPS_SENTENCE_THS:
380
if (_last_AGRICA_ms != 0 || _expect_agrica) {
381
// use AGRICA
382
break;
383
}
384
if (isnan(_new_gps_yaw)) {
385
// empty sentence
386
break;
387
}
388
_last_yaw_ms = now;
389
state.gps_yaw = wrap_360(_new_gps_yaw*0.01f);
390
state.have_gps_yaw = true;
391
state.gps_yaw_time_ms = now;
392
// remember that we are setup to provide yaw. With
393
// a NMEA GPS we can only tell if the GPS is
394
// configured to provide yaw when it first sends a
395
// HDT sentence.
396
state.gps_yaw_configured = true;
397
break;
398
case _GPS_SENTENCE_PHD:
399
if (_last_AGRICA_ms != 0) {
400
// prefer AGRICA
401
break;
402
}
403
if (_phd.msg_id == 12) {
404
state.velocity.x = _phd.fields[0] * 0.01;
405
state.velocity.y = _phd.fields[1] * 0.01;
406
state.velocity.z = _phd.fields[2] * 0.01;
407
state.have_vertical_velocity = true;
408
_last_vvelocity_ms = now;
409
// we prefer a true 3D velocity when available
410
velocity_to_speed_course(state);
411
_last_3D_velocity_ms = now;
412
} else if (_phd.msg_id == 26) {
413
state.horizontal_accuracy = MAX(_phd.fields[0],_phd.fields[1]) * 0.001;
414
state.have_horizontal_accuracy = true;
415
state.vertical_accuracy = _phd.fields[2] * 0.001;
416
state.have_vertical_accuracy = true;
417
state.speed_accuracy = MAX(_phd.fields[3],_phd.fields[4]) * 0.001;
418
state.have_speed_accuracy = true;
419
_last_vaccuracy_ms = now;
420
}
421
break;
422
case _GPS_SENTENCE_KSXT:
423
if (_last_AGRICA_ms != 0 || _expect_agrica) {
424
// prefer AGRICA
425
break;
426
}
427
state.location.lat = _ksxt.fields[2]*1.0e7;
428
state.location.lng = _ksxt.fields[1]*1.0e7;
429
set_alt_amsl_cm(state, _ksxt.fields[3]*1.0e2);
430
_last_KSXT_pos_ms = now;
431
if (_ksxt.fields[9] >= 1) {
432
// we have 3D fix
433
constexpr float kmh_to_mps = 1.0 / 3.6;
434
state.velocity.y = _ksxt.fields[16] * kmh_to_mps;
435
state.velocity.x = _ksxt.fields[17] * kmh_to_mps;
436
state.velocity.z = _ksxt.fields[18] * -kmh_to_mps;
437
state.have_vertical_velocity = true;
438
_last_vvelocity_ms = now;
439
// we prefer a true 3D velocity when available
440
velocity_to_speed_course(state);
441
_last_3D_velocity_ms = now;
442
}
443
if (is_equal(3.0f, float(_ksxt.fields[10]))) {
444
// have good yaw (from RTK fixed moving baseline solution)
445
_last_yaw_ms = now;
446
state.gps_yaw = _ksxt.fields[4];
447
state.have_gps_yaw = true;
448
state.gps_yaw_time_ms = now;
449
state.gps_yaw_configured = true;
450
}
451
break;
452
#if AP_GPS_NMEA_UNICORE_ENABLED
453
case _GPS_SENTENCE_AGRICA: {
454
const auto &ag = _agrica;
455
_last_AGRICA_ms = now;
456
_last_vvelocity_ms = now;
457
_last_vaccuracy_ms = now;
458
_last_3D_velocity_ms = now;
459
state.location.lat = ag.lat*1.0e7;
460
state.location.lng = ag.lng*1.0e7;
461
state.undulation = -ag.undulation;
462
state.have_undulation = true;
463
set_alt_amsl_cm(state, ag.alt*1.0e2);
464
state.velocity = ag.vel_NED;
465
velocity_to_speed_course(state);
466
state.speed_accuracy = ag.vel_stddev.length();
467
state.horizontal_accuracy = ag.pos_stddev.xy().length();
468
state.vertical_accuracy = ag.pos_stddev.z;
469
state.have_vertical_velocity = true;
470
state.have_speed_accuracy = true;
471
state.have_horizontal_accuracy = true;
472
state.have_vertical_accuracy = true;
473
check_new_itow(ag.itow, _sentence_length);
474
break;
475
}
476
case _GPS_SENTENCE_VERSIONA: {
477
_have_unicore_versiona = true;
478
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
479
"NMEA %s %s %s",
480
_versiona.type,
481
_versiona.version,
482
_versiona.build_date);
483
break;
484
}
485
case _GPS_SENTENCE_UNIHEADINGA: {
486
#if GPS_MOVING_BASELINE
487
const auto &ag = _agrica;
488
const auto &uh = _uniheadinga;
489
if (now - _last_AGRICA_ms > 500 || ag.heading_status != 4) {
490
// we need heading_status from AGRICA
491
state.have_gps_yaw = false;
492
break;
493
}
494
const float dist = uh.baseline_length;
495
const float bearing = uh.heading;
496
const float alt_diff = dist*tanf(radians(-uh.pitch));
497
state.relPosHeading = bearing;
498
state.relPosLength = dist;
499
state.relPosD = alt_diff;
500
state.relposheading_ts = now;
501
if (calculate_moving_base_yaw(bearing, dist, alt_diff)) {
502
state.have_gps_yaw_accuracy = true;
503
state.gps_yaw_accuracy = uh.heading_sd;
504
_last_yaw_ms = now;
505
}
506
state.gps_yaw_configured = true;
507
#endif // GPS_MOVING_BASELINE
508
break;
509
}
510
#endif // AP_GPS_NMEA_UNICORE_ENABLED
511
}
512
// see if we got a good message
513
return _have_new_message();
514
}
515
// we got a bad message, ignore it
516
return false;
517
}
518
519
// the first term determines the sentence type
520
if (_term_number == 0) {
521
/*
522
special case for $PHD message
523
*/
524
if (strcmp(_term, "PHD") == 0) {
525
_sentence_type = _GPS_SENTENCE_PHD;
526
return false;
527
}
528
if (strcmp(_term, "KSXT") == 0) {
529
_sentence_type = _GPS_SENTENCE_KSXT;
530
return false;
531
}
532
#if AP_GPS_NMEA_UNICORE_ENABLED
533
if (strcmp(_term, "AGRICA") == 0 && _expect_agrica) {
534
_sentence_type = _GPS_SENTENCE_AGRICA;
535
return false;
536
}
537
if (strcmp(_term, "VERSIONA") == 0) {
538
_sentence_type = _GPS_SENTENCE_VERSIONA;
539
return false;
540
}
541
if (strcmp(_term, "UNIHEADINGA") == 0 && _expect_agrica) {
542
_sentence_type = _GPS_SENTENCE_UNIHEADINGA;
543
return false;
544
}
545
#endif
546
/*
547
The first two letters of the NMEA term are the talker
548
ID. The most common is 'GP' but there are a bunch of others
549
that are valid. We accept any two characters here.
550
*/
551
if (_term[0] < 'A' || _term[0] > 'Z' ||
552
_term[1] < 'A' || _term[1] > 'Z') {
553
_sentence_type = _GPS_SENTENCE_OTHER;
554
return false;
555
}
556
const char *term_type = &_term[2];
557
if (strcmp(term_type, "RMC") == 0) {
558
_sentence_type = _GPS_SENTENCE_RMC;
559
} else if (strcmp(term_type, "GGA") == 0) {
560
_sentence_type = _GPS_SENTENCE_GGA;
561
} else if (strcmp(term_type, "HDT") == 0) {
562
_sentence_type = _GPS_SENTENCE_HDT;
563
} else if (strcmp(term_type, "THS") == 0) {
564
_sentence_type = _GPS_SENTENCE_THS;
565
} else if (strcmp(term_type, "VTG") == 0) {
566
_sentence_type = _GPS_SENTENCE_VTG;
567
} else {
568
_sentence_type = _GPS_SENTENCE_OTHER;
569
}
570
return false;
571
}
572
573
// 32 = RMC, 64 = GGA, 96 = VTG, 128 = HDT, 160 = THS
574
if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0]) {
575
switch (_sentence_type + _term_number) {
576
// operational status
577
//
578
case _GPS_SENTENCE_RMC + 2: // validity (RMC)
579
break;
580
case _GPS_SENTENCE_GGA + 6: // Fix data (GGA)
581
if (_term[0] > '0') {
582
_new_quality_indicator = _term[0] - '0';
583
} else {
584
_new_quality_indicator = 0;
585
}
586
break;
587
case _GPS_SENTENCE_GGA + 7: // satellite count (GGA)
588
_new_satellite_count = atol(_term);
589
break;
590
case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)
591
_new_hdop = (uint16_t)_parse_decimal_100(_term);
592
break;
593
594
// time and date
595
//
596
case _GPS_SENTENCE_RMC + 1: // Time (RMC)
597
case _GPS_SENTENCE_GGA + 1: // Time (GGA)
598
_new_time = _parse_decimal_100(_term);
599
break;
600
case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)
601
_new_date = atol(_term);
602
break;
603
604
// location
605
//
606
case _GPS_SENTENCE_RMC + 3: // Latitude
607
case _GPS_SENTENCE_GGA + 2:
608
_new_latitude = _parse_degrees();
609
break;
610
case _GPS_SENTENCE_RMC + 4: // N/S
611
case _GPS_SENTENCE_GGA + 3:
612
if (_term[0] == 'S')
613
_new_latitude = -_new_latitude;
614
break;
615
case _GPS_SENTENCE_RMC + 5: // Longitude
616
case _GPS_SENTENCE_GGA + 4:
617
_new_longitude = _parse_degrees();
618
break;
619
case _GPS_SENTENCE_RMC + 6: // E/W
620
case _GPS_SENTENCE_GGA + 5:
621
if (_term[0] == 'W')
622
_new_longitude = -_new_longitude;
623
break;
624
case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)
625
_new_altitude = _parse_decimal_100(_term);
626
break;
627
628
// course and speed
629
//
630
case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
631
case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
632
_new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximates * 0.514
633
break;
634
case _GPS_SENTENCE_HDT + 1: // Course (HDT)
635
_new_gps_yaw = _parse_decimal_100(_term);
636
break;
637
case _GPS_SENTENCE_THS + 1: // Course (THS)
638
_new_gps_yaw = _parse_decimal_100(_term);
639
break;
640
case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)
641
case _GPS_SENTENCE_VTG + 1: // Course (VTG)
642
_new_course = _parse_decimal_100(_term);
643
break;
644
645
case _GPS_SENTENCE_PHD + 1: // PHD class
646
_phd.msg_class = atol(_term);
647
break;
648
case _GPS_SENTENCE_PHD + 2: // PHD message
649
_phd.msg_id = atol(_term);
650
break;
651
case _GPS_SENTENCE_PHD + 5: // PHD message, itow
652
_phd.itow = strtoul(_term, nullptr, 10);
653
break;
654
case _GPS_SENTENCE_PHD + 6 ... _GPS_SENTENCE_PHD + 11: // PHD message, fields
655
_phd.fields[_term_number-6] = atol(_term);
656
break;
657
case _GPS_SENTENCE_KSXT + 1 ... _GPS_SENTENCE_KSXT + 22: // KSXT message, fields
658
_ksxt.fields[_term_number-1] = atof(_term);
659
break;
660
#if AP_GPS_NMEA_UNICORE_ENABLED
661
case _GPS_SENTENCE_AGRICA + 1 ... _GPS_SENTENCE_AGRICA + 65: // AGRICA message
662
parse_agrica_field(_term_number, _term);
663
break;
664
case _GPS_SENTENCE_VERSIONA + 1 ... _GPS_SENTENCE_VERSIONA + 20:
665
parse_versiona_field(_term_number, _term);
666
break;
667
#if GPS_MOVING_BASELINE
668
case _GPS_SENTENCE_UNIHEADINGA + 1 ... _GPS_SENTENCE_UNIHEADINGA + 28: // UNIHEADINGA message
669
parse_uniheadinga_field(_term_number, _term);
670
break;
671
#endif
672
#endif
673
}
674
}
675
676
return false;
677
}
678
679
#if AP_GPS_NMEA_UNICORE_ENABLED
680
/*
681
parse an AGRICA message term
682
683
Example:
684
#AGRICA,82,GPS,FINE,2237,176366400,0,0,18,15;GNSS,232,22,11,22,0,59,8,1,5,8,12,0,0.0000,0.0000,0.0000,0.0000,0.0000,0.0000,296.4656,-26.5685,0.0000,0.005,0.000,0.000,-0.005,0.044,0.032,0.038,-35.33142715815,149.13181842030,609.1494,-4471799.0368,2672944.7758,-3668288.9857,1.3923,1.5128,3.2272,2.3026,2.1633,2.1586,0.00000000000,0.00000000000,0.0000,0.00000000000,0.00000000000,0.0000,176366400,0.000,66.175285,18.972784,0.000000,0.000000,5,0,0,0*9f704dad
685
*/
686
void AP_GPS_NMEA::parse_agrica_field(uint16_t term_number, const char *term)
687
{
688
auto &ag = _agrica;
689
// subtract 8 to align term numbers with reference manual
690
// look for "Unicore Reference Command Manual" to find the specification
691
const uint8_t hdr_align = 8;
692
if (term_number < hdr_align) {
693
// discard header;
694
return;
695
}
696
term_number -= hdr_align;
697
// useful for debugging
698
//::printf("AGRICA[%u]=%s\n", unsigned(term_number), term);
699
switch (term_number) {
700
case 10:
701
ag.rtk_status = atol(term);
702
break;
703
case 11:
704
ag.heading_status = atol(term);
705
break;
706
case 25 ... 26:
707
ag.vel_NED[term_number-25] = atof(term);
708
break;
709
case 27:
710
// AGRIC gives velocity up
711
ag.vel_NED.z = -atof(term);
712
break;
713
case 28 ... 30:
714
ag.vel_stddev[term_number-28] = atof(term);
715
break;
716
case 31:
717
ag.lat = atof(term);
718
break;
719
case 32:
720
ag.lng = atof(term);
721
break;
722
case 33:
723
ag.alt = atof(term);
724
break;
725
case 49:
726
ag.itow = atol(term);
727
break;
728
case 37 ... 39:
729
ag.pos_stddev[term_number-37] = atof(term);
730
break;
731
case 52:
732
ag.undulation = atof(term);
733
break;
734
}
735
}
736
737
#if GPS_MOVING_BASELINE
738
/*
739
parse a UNIHEADINGA message term
740
741
Example:
742
#UNIHEADINGA,79,GPS,FINE,2242,167498200,0,0,18,22;SOL_COMPUTED,L1_INT,2.7889,296.7233,-25.7710,0.0000,0.1127,0.1812,"999",49,37,37,0,3,00,1,51*d50af0ea
743
*/
744
void AP_GPS_NMEA::parse_uniheadinga_field(uint16_t term_number, const char *term)
745
{
746
const uint8_t hdr_align = 8;
747
if (term_number < hdr_align) {
748
// discard header;
749
return;
750
}
751
term_number -= hdr_align;
752
// useful for debugging
753
// ::printf("UNIHEADINGA[%u]=%s\n", unsigned(term_number), term);
754
auto &uh = _uniheadinga;
755
switch (term_number) {
756
case 4:
757
uh.baseline_length = atof(term);
758
break;
759
case 5:
760
uh.heading = atof(term);
761
break;
762
case 6:
763
uh.pitch = atof(term);
764
break;
765
case 8:
766
uh.heading_sd = atof(term);
767
break;
768
}
769
}
770
#endif // GPS_MOVING_BASELINE
771
772
// parse VERSIONA fields
773
void AP_GPS_NMEA::parse_versiona_field(uint16_t term_number, const char *term)
774
{
775
// printf useful for debugging
776
// ::printf("VERSIONA[%u]='%s'\n", term_number, term);
777
auto &v = _versiona;
778
#pragma GCC diagnostic push
779
#if defined(__GNUC__) && __GNUC__ >= 9
780
#pragma GCC diagnostic ignored "-Wstringop-truncation"
781
#endif
782
switch (term_number) {
783
case 10:
784
strncpy(v.type, _term, sizeof(v.type)-1);
785
break;
786
case 11:
787
strncpy(v.version, _term, sizeof(v.version)-1);
788
break;
789
case 15:
790
strncpy(v.build_date, _term, sizeof(v.build_date)-1);
791
break;
792
}
793
#pragma GCC diagnostic pop
794
}
795
#endif // AP_GPS_NMEA_UNICORE_ENABLED
796
797
/*
798
detect a NMEA GPS. Adds one byte, and returns true if the stream
799
matches a NMEA string
800
*/
801
bool
802
AP_GPS_NMEA::_detect(struct NMEA_detect_state &state, uint8_t data)
803
{
804
switch (state.step) {
805
case 0:
806
state.ck = 0;
807
if ('$' == data) {
808
state.step++;
809
}
810
break;
811
case 1:
812
if ('*' == data) {
813
state.step++;
814
} else {
815
state.ck ^= data;
816
}
817
break;
818
case 2:
819
if (hexdigit(state.ck>>4) == data) {
820
state.step++;
821
} else {
822
state.step = 0;
823
}
824
break;
825
case 3:
826
if (hexdigit(state.ck&0xF) == data) {
827
state.step = 0;
828
return true;
829
}
830
state.step = 0;
831
break;
832
}
833
return false;
834
}
835
836
/*
837
send type specific config strings
838
*/
839
void AP_GPS_NMEA::send_config(void)
840
{
841
const auto type = get_type();
842
_expect_agrica = (type == AP_GPS::GPS_TYPE_UNICORE_NMEA ||
843
type == AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA);
844
if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
845
// not doing auto-config
846
return;
847
}
848
uint32_t now_ms = AP_HAL::millis();
849
if (now_ms - last_config_ms < AP_GPS_NMEA_CONFIG_PERIOD_MS) {
850
return;
851
}
852
last_config_ms = now_ms;
853
const uint16_t rate_ms = params.rate_ms;
854
#if AP_GPS_NMEA_UNICORE_ENABLED
855
const float rate_s = rate_ms * 0.001;
856
#endif
857
const uint8_t rate_hz = 1000U / rate_ms;
858
859
switch (get_type()) {
860
#if AP_GPS_NMEA_UNICORE_ENABLED
861
case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:
862
port->printf("\r\nCONFIG HEADING FIXLENGTH\r\n" \
863
"CONFIG UNDULATION AUTO\r\n" \
864
"CONFIG\r\n" \
865
"UNIHEADINGA %.3f\r\n",
866
rate_s);
867
state.gps_yaw_configured = true;
868
FALLTHROUGH;
869
870
case AP_GPS::GPS_TYPE_UNICORE_NMEA: {
871
port->printf("\r\nAGRICA %.3f\r\n" \
872
"MODE MOVINGBASE\r\n" \
873
"GNGGA %.3f\r\n" \
874
"GNRMC %.3f\r\n",
875
rate_s, rate_s, rate_s);
876
if (!_have_unicore_versiona) {
877
// get version information for logging if we don't have it yet
878
port->printf("VERSIONA\r\n");
879
if (gps._save_config) {
880
// save config changes for fast startup
881
port->printf("SAVECONFIG\r\n");
882
}
883
}
884
break;
885
}
886
#endif // AP_GPS_NMEA_UNICORE_ENABLED
887
888
case AP_GPS::GPS_TYPE_HEMI: {
889
port->printf(
890
"$JATT,NMEAHE,0\r\n" /* Prefix of GP on the HDT message */ \
891
"$JASC,GPGGA,%u\r\n" /* GGA at 5Hz */ \
892
"$JASC,GPRMC,%u\r\n" /* RMC at 5Hz */ \
893
"$JASC,GPVTG,%u\r\n" /* VTG at 5Hz */ \
894
"$JASC,GPHDT,%u\r\n" /* HDT at 5Hz */ \
895
"$JMODE,SBASR,YES\r\n" /* Enable SBAS */,
896
rate_hz, rate_hz, rate_hz, rate_hz);
897
break;
898
}
899
900
case AP_GPS::GPS_TYPE_ALLYSTAR:
901
nmea_printf(port, "$PHD,06,42,UUUUTTTT,BB,0,%u,55,0,%u,0,0,0",
902
unsigned(rate_hz), unsigned(rate_ms));
903
break;
904
905
default:
906
break;
907
}
908
909
#ifdef AP_GPS_NMEA_CUSTOM_CONFIG_STRING
910
// allow for custom config strings, useful for peripherals
911
port->printf("%s\r\n", AP_GPS_NMEA_CUSTOM_CONFIG_STRING);
912
#endif
913
}
914
915
/*
916
return health status
917
*/
918
bool AP_GPS_NMEA::is_healthy(void) const
919
{
920
switch (get_type()) {
921
#if AP_GPS_NMEA_UNICORE_ENABLED
922
case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:
923
case AP_GPS::GPS_TYPE_UNICORE_NMEA:
924
// we should be getting AGRICA messages
925
return _last_AGRICA_ms != 0;
926
#endif // AP_GPS_NMEA_UNICORE_ENABLED
927
928
case AP_GPS::GPS_TYPE_HEMI:
929
// we should be getting HDR for yaw
930
return _last_yaw_ms != 0;
931
932
case AP_GPS::GPS_TYPE_ALLYSTAR:
933
// we should get vertical velocity and accuracy from PHD
934
return _last_vvelocity_ms != 0 && _last_vaccuracy_ms != 0;
935
936
default:
937
break;
938
}
939
return true;
940
}
941
942
// get the velocity lag
943
bool AP_GPS_NMEA::get_lag(float &lag_sec) const
944
{
945
switch (get_type()) {
946
#if AP_GPS_NMEA_UNICORE_ENABLED
947
case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:
948
case AP_GPS::GPS_TYPE_UNICORE_NMEA:
949
lag_sec = 0.14;
950
break;
951
#endif // AP_GPS_NMEA_UNICORE_ENABLED
952
953
default:
954
lag_sec = 0.2;
955
break;
956
}
957
return true;
958
}
959
960
#if HAL_LOGGING_ENABLED
961
void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const
962
{
963
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
964
#if AP_GPS_NMEA_UNICORE_ENABLED
965
if (_have_unicore_versiona) {
966
AP::logger().Write_MessageF("NMEA %u %s %s %s",
967
state.instance+1,
968
_versiona.type,
969
_versiona.version,
970
_versiona.build_date);
971
}
972
#endif
973
}
974
#endif
975
976
#endif // AP_GPS_NMEA_ENABLED
977
978