AP_GPS_NMEA.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. // NMEA parser, adapted by Michael Smith from TinyGPS v9:
  15. //
  16. // TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
  17. // Copyright (C) 2008-9 Mikal Hart
  18. // All rights reserved.
  19. //
  20. /// @file AP_GPS_NMEA.cpp
  21. /// @brief NMEA protocol parser
  22. ///
  23. /// This is a lightweight NMEA parser, derived originally from the
  24. /// TinyGPS parser by Mikal Hart.
  25. ///
  26. #include <AP_Common/AP_Common.h>
  27. #include <ctype.h>
  28. #include <stdint.h>
  29. #include <stdlib.h>
  30. #include "AP_GPS_NMEA.h"
  31. extern const AP_HAL::HAL& hal;
  32. // optionally log all NMEA data for debug purposes
  33. // #define NMEA_LOG_PATH "nmea.log"
  34. #ifdef NMEA_LOG_PATH
  35. #include <stdio.h>
  36. #endif
  37. // Convenience macros //////////////////////////////////////////////////////////
  38. //
  39. #define DIGIT_TO_VAL(_x) (_x - '0')
  40. #define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x))
  41. bool AP_GPS_NMEA::read(void)
  42. {
  43. int16_t numc;
  44. bool parsed = false;
  45. numc = port->available();
  46. while (numc--) {
  47. char c = port->read();
  48. #ifdef NMEA_LOG_PATH
  49. static FILE *logf = nullptr;
  50. if (logf == nullptr) {
  51. logf = fopen(NMEA_LOG_PATH, "wb");
  52. }
  53. if (logf != nullptr) {
  54. ::fwrite(&c, 1, 1, logf);
  55. }
  56. #endif
  57. if (_decode(c)) {
  58. parsed = true;
  59. }
  60. }
  61. return parsed;
  62. }
  63. bool AP_GPS_NMEA::_decode(char c)
  64. {
  65. bool valid_sentence = false;
  66. _sentence_length++;
  67. switch (c) {
  68. case ',': // term terminators
  69. _parity ^= c;
  70. FALLTHROUGH;
  71. case '\r':
  72. case '\n':
  73. case '*':
  74. if (_term_offset < sizeof(_term)) {
  75. _term[_term_offset] = 0;
  76. valid_sentence = _term_complete();
  77. }
  78. ++_term_number;
  79. _term_offset = 0;
  80. _is_checksum_term = c == '*';
  81. return valid_sentence;
  82. case '$': // sentence begin
  83. _term_number = _term_offset = 0;
  84. _parity = 0;
  85. _sentence_type = _GPS_SENTENCE_OTHER;
  86. _is_checksum_term = false;
  87. _gps_data_good = false;
  88. _sentence_length = 1;
  89. return valid_sentence;
  90. }
  91. // ordinary characters
  92. if (_term_offset < sizeof(_term) - 1)
  93. _term[_term_offset++] = c;
  94. if (!_is_checksum_term)
  95. _parity ^= c;
  96. return valid_sentence;
  97. }
  98. int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
  99. {
  100. char *endptr = nullptr;
  101. long ret = 100 * strtol(p, &endptr, 10);
  102. int sign = ret < 0 ? -1 : 1;
  103. if (ret >= (long)INT32_MAX) {
  104. return INT32_MAX;
  105. }
  106. if (ret <= (long)INT32_MIN) {
  107. return INT32_MIN;
  108. }
  109. if (endptr == nullptr || *endptr != '.') {
  110. return ret;
  111. }
  112. if (isdigit(endptr[1])) {
  113. ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);
  114. if (isdigit(endptr[2])) {
  115. ret += sign * DIGIT_TO_VAL(endptr[2]);
  116. if (isdigit(endptr[3])) {
  117. ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);
  118. }
  119. }
  120. }
  121. return ret;
  122. }
  123. /*
  124. parse a NMEA latitude/longitude degree value. The result is in degrees*1e7
  125. */
  126. uint32_t AP_GPS_NMEA::_parse_degrees()
  127. {
  128. char *p, *q;
  129. uint8_t deg = 0, min = 0;
  130. float frac_min = 0;
  131. int32_t ret = 0;
  132. // scan for decimal point or end of field
  133. for (p = _term; *p && isdigit(*p); p++)
  134. ;
  135. q = _term;
  136. // convert degrees
  137. while ((p - q) > 2 && *q) {
  138. if (deg)
  139. deg *= 10;
  140. deg += DIGIT_TO_VAL(*q++);
  141. }
  142. // convert minutes
  143. while (p > q && *q) {
  144. if (min)
  145. min *= 10;
  146. min += DIGIT_TO_VAL(*q++);
  147. }
  148. // convert fractional minutes
  149. if (*p == '.') {
  150. q = p + 1;
  151. float frac_scale = 0.1f;
  152. while (*q && isdigit(*q)) {
  153. frac_min += DIGIT_TO_VAL(*q) * frac_scale;
  154. q++;
  155. frac_scale *= 0.1f;
  156. }
  157. }
  158. ret = (deg * (int32_t)10000000UL);
  159. ret += (min * (int32_t)10000000UL / 60);
  160. ret += (int32_t) (frac_min * (1.0e7f / 60.0f));
  161. return ret;
  162. }
  163. /*
  164. see if we have a new set of NMEA messages
  165. */
  166. bool AP_GPS_NMEA::_have_new_message()
  167. {
  168. if (_last_RMC_ms == 0 ||
  169. _last_GGA_ms == 0) {
  170. return false;
  171. }
  172. uint32_t now = AP_HAL::millis();
  173. if (now - _last_RMC_ms > 150 ||
  174. now - _last_GGA_ms > 150) {
  175. return false;
  176. }
  177. if (_last_VTG_ms != 0 &&
  178. now - _last_VTG_ms > 150) {
  179. return false;
  180. }
  181. // prevent these messages being used again
  182. if (_last_VTG_ms != 0) {
  183. _last_VTG_ms = 1;
  184. }
  185. if (now - _last_HDT_ms > 300) {
  186. // we have lost GPS yaw
  187. state.have_gps_yaw = false;
  188. }
  189. _last_GGA_ms = 1;
  190. _last_RMC_ms = 1;
  191. return true;
  192. }
  193. // Processes a just-completed term
  194. // Returns true if new sentence has just passed checksum test and is validated
  195. bool AP_GPS_NMEA::_term_complete()
  196. {
  197. // handle the last term in a message
  198. if (_is_checksum_term) {
  199. uint8_t nibble_high = 0;
  200. uint8_t nibble_low = 0;
  201. if (!hex_to_uint8(_term[0], nibble_high) || !hex_to_uint8(_term[1], nibble_low)) {
  202. return false;
  203. }
  204. const uint8_t checksum = (nibble_high << 4u) | nibble_low;
  205. if (checksum == _parity) {
  206. if (_gps_data_good) {
  207. uint32_t now = AP_HAL::millis();
  208. switch (_sentence_type) {
  209. case _GPS_SENTENCE_RMC:
  210. _last_RMC_ms = now;
  211. //time = _new_time;
  212. //date = _new_date;
  213. state.location.lat = _new_latitude;
  214. state.location.lng = _new_longitude;
  215. state.ground_speed = _new_speed*0.01f;
  216. state.ground_course = wrap_360(_new_course*0.01f);
  217. make_gps_time(_new_date, _new_time * 10);
  218. set_uart_timestamp(_sentence_length);
  219. state.last_gps_time_ms = now;
  220. fill_3d_velocity();
  221. break;
  222. case _GPS_SENTENCE_GGA:
  223. _last_GGA_ms = now;
  224. state.location.alt = _new_altitude;
  225. state.location.lat = _new_latitude;
  226. state.location.lng = _new_longitude;
  227. state.num_sats = _new_satellite_count;
  228. state.hdop = _new_hdop;
  229. switch(_new_quality_indicator) {
  230. case 0: // Fix not available or invalid
  231. state.status = AP_GPS::NO_FIX;
  232. break;
  233. case 1: // GPS SPS Mode, fix valid
  234. state.status = AP_GPS::GPS_OK_FIX_3D;
  235. break;
  236. case 2: // Differential GPS, SPS Mode, fix valid
  237. state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
  238. break;
  239. case 3: // GPS PPS Mode, fix valid
  240. state.status = AP_GPS::GPS_OK_FIX_3D;
  241. break;
  242. case 4: // Real Time Kinematic. System used in RTK mode with fixed integers
  243. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  244. break;
  245. case 5: // Float RTK. Satellite system used in RTK mode, floating integers
  246. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  247. break;
  248. case 6: // Estimated (dead reckoning) Mode
  249. state.status = AP_GPS::NO_FIX;
  250. break;
  251. default://to maintain compatibility with MAV_GPS_INPUT and others
  252. state.status = AP_GPS::GPS_OK_FIX_3D;
  253. break;
  254. }
  255. break;
  256. case _GPS_SENTENCE_VTG:
  257. _last_VTG_ms = now;
  258. state.ground_speed = _new_speed*0.01f;
  259. state.ground_course = wrap_360(_new_course*0.01f);
  260. fill_3d_velocity();
  261. // VTG has no fix indicator, can't change fix status
  262. break;
  263. case _GPS_SENTENCE_HDT:
  264. _last_HDT_ms = now;
  265. state.gps_yaw = wrap_360(_new_gps_yaw*0.01f);
  266. state.have_gps_yaw = true;
  267. break;
  268. }
  269. } else {
  270. switch (_sentence_type) {
  271. case _GPS_SENTENCE_RMC:
  272. case _GPS_SENTENCE_GGA:
  273. // Only these sentences give us information about
  274. // fix status.
  275. state.status = AP_GPS::NO_FIX;
  276. }
  277. }
  278. // see if we got a good message
  279. return _have_new_message();
  280. }
  281. // we got a bad message, ignore it
  282. return false;
  283. }
  284. // the first term determines the sentence type
  285. if (_term_number == 0) {
  286. /*
  287. The first two letters of the NMEA term are the talker
  288. ID. The most common is 'GP' but there are a bunch of others
  289. that are valid. We accept any two characters here.
  290. */
  291. if (_term[0] < 'A' || _term[0] > 'Z' ||
  292. _term[1] < 'A' || _term[1] > 'Z') {
  293. _sentence_type = _GPS_SENTENCE_OTHER;
  294. return false;
  295. }
  296. const char *term_type = &_term[2];
  297. if (strcmp(term_type, "RMC") == 0) {
  298. _sentence_type = _GPS_SENTENCE_RMC;
  299. } else if (strcmp(term_type, "GGA") == 0) {
  300. _sentence_type = _GPS_SENTENCE_GGA;
  301. } else if (strcmp(term_type, "HDT") == 0) {
  302. _sentence_type = _GPS_SENTENCE_HDT;
  303. // HDT doesn't have a data qualifier
  304. _gps_data_good = true;
  305. } else if (strcmp(term_type, "VTG") == 0) {
  306. _sentence_type = _GPS_SENTENCE_VTG;
  307. // VTG may not contain a data qualifier, presume the solution is good
  308. // unless it tells us otherwise.
  309. _gps_data_good = true;
  310. } else {
  311. _sentence_type = _GPS_SENTENCE_OTHER;
  312. }
  313. return false;
  314. }
  315. // 32 = RMC, 64 = GGA, 96 = VTG, 128 = HDT
  316. if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0]) {
  317. switch (_sentence_type + _term_number) {
  318. // operational status
  319. //
  320. case _GPS_SENTENCE_RMC + 2: // validity (RMC)
  321. _gps_data_good = _term[0] == 'A';
  322. break;
  323. case _GPS_SENTENCE_GGA + 6: // Fix data (GGA)
  324. _gps_data_good = _term[0] > '0';
  325. _new_quality_indicator = _term[0] - '0';
  326. break;
  327. case _GPS_SENTENCE_VTG + 9: // validity (VTG) (we may not see this field)
  328. _gps_data_good = _term[0] != 'N';
  329. break;
  330. case _GPS_SENTENCE_GGA + 7: // satellite count (GGA)
  331. _new_satellite_count = atol(_term);
  332. break;
  333. case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)
  334. _new_hdop = (uint16_t)_parse_decimal_100(_term);
  335. break;
  336. // time and date
  337. //
  338. case _GPS_SENTENCE_RMC + 1: // Time (RMC)
  339. case _GPS_SENTENCE_GGA + 1: // Time (GGA)
  340. _new_time = _parse_decimal_100(_term);
  341. break;
  342. case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)
  343. _new_date = atol(_term);
  344. break;
  345. // location
  346. //
  347. case _GPS_SENTENCE_RMC + 3: // Latitude
  348. case _GPS_SENTENCE_GGA + 2:
  349. _new_latitude = _parse_degrees();
  350. break;
  351. case _GPS_SENTENCE_RMC + 4: // N/S
  352. case _GPS_SENTENCE_GGA + 3:
  353. if (_term[0] == 'S')
  354. _new_latitude = -_new_latitude;
  355. break;
  356. case _GPS_SENTENCE_RMC + 5: // Longitude
  357. case _GPS_SENTENCE_GGA + 4:
  358. _new_longitude = _parse_degrees();
  359. break;
  360. case _GPS_SENTENCE_RMC + 6: // E/W
  361. case _GPS_SENTENCE_GGA + 5:
  362. if (_term[0] == 'W')
  363. _new_longitude = -_new_longitude;
  364. break;
  365. case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)
  366. _new_altitude = _parse_decimal_100(_term);
  367. break;
  368. // course and speed
  369. //
  370. case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
  371. case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
  372. _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514
  373. break;
  374. case _GPS_SENTENCE_HDT + 1: // Course (HDT)
  375. _new_gps_yaw = _parse_decimal_100(_term);
  376. break;
  377. case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)
  378. case _GPS_SENTENCE_VTG + 1: // Course (VTG)
  379. _new_course = _parse_decimal_100(_term);
  380. break;
  381. }
  382. }
  383. return false;
  384. }
  385. /*
  386. detect a NMEA GPS. Adds one byte, and returns true if the stream
  387. matches a NMEA string
  388. */
  389. bool
  390. AP_GPS_NMEA::_detect(struct NMEA_detect_state &state, uint8_t data)
  391. {
  392. switch (state.step) {
  393. case 0:
  394. state.ck = 0;
  395. if ('$' == data) {
  396. state.step++;
  397. }
  398. break;
  399. case 1:
  400. if ('*' == data) {
  401. state.step++;
  402. } else {
  403. state.ck ^= data;
  404. }
  405. break;
  406. case 2:
  407. if (hexdigit(state.ck>>4) == data) {
  408. state.step++;
  409. } else {
  410. state.step = 0;
  411. }
  412. break;
  413. case 3:
  414. if (hexdigit(state.ck&0xF) == data) {
  415. state.step = 0;
  416. return true;
  417. }
  418. state.step = 0;
  419. break;
  420. }
  421. return false;
  422. }