AP_GPS_UBLOX.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611
  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. // u-blox UBX GPS driver for ArduPilot and ArduPilotMega.
  15. // Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
  16. //
  17. // UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
  18. #pragma once
  19. #include <AP_HAL/AP_HAL.h>
  20. #include "AP_GPS.h"
  21. #include "GPS_Backend.h"
  22. /*
  23. * try to put a UBlox into binary mode. This is in two parts.
  24. *
  25. * First we send a ubx binary message that enables the NAV_SOL message
  26. * at rate 1. Then we send a NMEA message to set the baud rate to our
  27. * desired rate. The reason for doing the NMEA message second is if we
  28. * send it first the second message will be ignored for a baud rate
  29. * change.
  30. * The reason we need the NAV_SOL rate message at all is some uBlox
  31. * modules are configured with all ubx binary messages off, which
  32. * would mean we would never detect it.
  33. */
  34. #define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n"
  35. #define UBLOX_RXM_RAW_LOGGING 1
  36. #define UBLOX_MAX_RXM_RAW_SATS 22
  37. #define UBLOX_MAX_RXM_RAWX_SATS 32
  38. #define UBLOX_GNSS_SETTINGS 1
  39. #define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7
  40. #define UBX_MSG_TYPES 2
  41. #define UBX_TIMEGPS_VALID_WEEK_MASK 0x2
  42. #define UBLOX_MAX_PORTS 6
  43. #define RATE_POSLLH 1
  44. #define RATE_STATUS 1
  45. #define RATE_SOL 1
  46. #define RATE_TIMEGPS 5
  47. #define RATE_PVT 1
  48. #define RATE_VELNED 1
  49. #define RATE_DOP 1
  50. #define RATE_HW 5
  51. #define RATE_HW2 5
  52. #define CONFIG_RATE_NAV (1<<0)
  53. #define CONFIG_RATE_POSLLH (1<<1)
  54. #define CONFIG_RATE_STATUS (1<<2)
  55. #define CONFIG_RATE_SOL (1<<3)
  56. #define CONFIG_RATE_VELNED (1<<4)
  57. #define CONFIG_RATE_DOP (1<<5)
  58. #define CONFIG_RATE_MON_HW (1<<6)
  59. #define CONFIG_RATE_MON_HW2 (1<<7)
  60. #define CONFIG_RATE_RAW (1<<8)
  61. #define CONFIG_VERSION (1<<9)
  62. #define CONFIG_NAV_SETTINGS (1<<10)
  63. #define CONFIG_GNSS (1<<11)
  64. #define CONFIG_SBAS (1<<12)
  65. #define CONFIG_RATE_PVT (1<<13)
  66. #define CONFIG_TP5 (1<<14)
  67. #define CONFIG_RATE_TIMEGPS (1<<15)
  68. #define CONFIG_LAST (1<<16) // this must always be the last bit
  69. #define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED)
  70. #define CONFIG_ALL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_SOL | CONFIG_RATE_VELNED \
  71. | CONFIG_RATE_DOP | CONFIG_RATE_MON_HW | CONFIG_RATE_MON_HW2 | CONFIG_RATE_RAW | CONFIG_VERSION \
  72. | CONFIG_NAV_SETTINGS | CONFIG_GNSS | CONFIG_SBAS)
  73. //Configuration Sub-Sections
  74. #define SAVE_CFG_IO (1<<0)
  75. #define SAVE_CFG_MSG (1<<1)
  76. #define SAVE_CFG_INF (1<<2)
  77. #define SAVE_CFG_NAV (1<<3)
  78. #define SAVE_CFG_RXM (1<<4)
  79. #define SAVE_CFG_RINV (1<<9)
  80. #define SAVE_CFG_ANT (1<<10)
  81. #define SAVE_CFG_ALL (SAVE_CFG_IO|SAVE_CFG_MSG|SAVE_CFG_INF|SAVE_CFG_NAV|SAVE_CFG_RXM|SAVE_CFG_RINV|SAVE_CFG_ANT)
  82. class AP_GPS_UBLOX : public AP_GPS_Backend
  83. {
  84. public:
  85. AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
  86. // Methods
  87. bool read() override;
  88. AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
  89. static bool _detect(struct UBLOX_detect_state &state, uint8_t data);
  90. bool is_configured(void) override {
  91. #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
  92. if (!gps._auto_config) {
  93. return true;
  94. } else {
  95. return !_unconfigured_messages;
  96. }
  97. #else
  98. return true;
  99. #endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
  100. }
  101. void broadcast_configuration_failure_reason(void) const override;
  102. void Write_AP_Logger_Log_Startup_messages() const override;
  103. // get the velocity lag, returns true if the driver is confident in the returned value
  104. bool get_lag(float &lag_sec) const override;
  105. const char *name() const override { return "u-blox"; }
  106. private:
  107. // u-blox UBX protocol essentials
  108. struct PACKED ubx_header {
  109. uint8_t preamble1;
  110. uint8_t preamble2;
  111. uint8_t msg_class;
  112. uint8_t msg_id;
  113. uint16_t length;
  114. };
  115. #if UBLOX_GNSS_SETTINGS
  116. struct PACKED ubx_cfg_gnss {
  117. uint8_t msgVer;
  118. uint8_t numTrkChHw;
  119. uint8_t numTrkChUse;
  120. uint8_t numConfigBlocks;
  121. PACKED struct configBlock {
  122. uint8_t gnssId;
  123. uint8_t resTrkCh;
  124. uint8_t maxTrkCh;
  125. uint8_t reserved1;
  126. uint32_t flags;
  127. } configBlock[UBLOX_MAX_GNSS_CONFIG_BLOCKS];
  128. };
  129. #endif
  130. struct PACKED ubx_cfg_nav_rate {
  131. uint16_t measure_rate_ms;
  132. uint16_t nav_rate;
  133. uint16_t timeref;
  134. };
  135. struct PACKED ubx_cfg_msg {
  136. uint8_t msg_class;
  137. uint8_t msg_id;
  138. };
  139. struct PACKED ubx_cfg_msg_rate {
  140. uint8_t msg_class;
  141. uint8_t msg_id;
  142. uint8_t rate;
  143. };
  144. struct PACKED ubx_cfg_msg_rate_6 {
  145. uint8_t msg_class;
  146. uint8_t msg_id;
  147. uint8_t rates[6];
  148. };
  149. struct PACKED ubx_cfg_nav_settings {
  150. uint16_t mask;
  151. uint8_t dynModel;
  152. uint8_t fixMode;
  153. int32_t fixedAlt;
  154. uint32_t fixedAltVar;
  155. int8_t minElev;
  156. uint8_t drLimit;
  157. uint16_t pDop;
  158. uint16_t tDop;
  159. uint16_t pAcc;
  160. uint16_t tAcc;
  161. uint8_t staticHoldThresh;
  162. uint8_t res1;
  163. uint32_t res2;
  164. uint32_t res3;
  165. uint32_t res4;
  166. };
  167. struct PACKED ubx_cfg_tp5 {
  168. uint8_t tpIdx;
  169. uint8_t version;
  170. uint8_t reserved1[2];
  171. int16_t antCableDelay;
  172. int16_t rfGroupDelay;
  173. uint32_t freqPeriod;
  174. uint32_t freqPeriodLock;
  175. uint32_t pulseLenRatio;
  176. uint32_t pulseLenRatioLock;
  177. int32_t userConfigDelay;
  178. uint32_t flags;
  179. };
  180. struct PACKED ubx_cfg_prt {
  181. uint8_t portID;
  182. };
  183. struct PACKED ubx_cfg_sbas {
  184. uint8_t mode;
  185. uint8_t usage;
  186. uint8_t maxSBAS;
  187. uint8_t scanmode2;
  188. uint32_t scanmode1;
  189. };
  190. struct PACKED ubx_nav_posllh {
  191. uint32_t itow; // GPS msToW
  192. int32_t longitude;
  193. int32_t latitude;
  194. int32_t altitude_ellipsoid;
  195. int32_t altitude_msl;
  196. uint32_t horizontal_accuracy;
  197. uint32_t vertical_accuracy;
  198. };
  199. struct PACKED ubx_nav_status {
  200. uint32_t itow; // GPS msToW
  201. uint8_t fix_type;
  202. uint8_t fix_status;
  203. uint8_t differential_status;
  204. uint8_t res;
  205. uint32_t time_to_first_fix;
  206. uint32_t uptime; // milliseconds
  207. };
  208. struct PACKED ubx_nav_dop {
  209. uint32_t itow; // GPS msToW
  210. uint16_t gDOP;
  211. uint16_t pDOP;
  212. uint16_t tDOP;
  213. uint16_t vDOP;
  214. uint16_t hDOP;
  215. uint16_t nDOP;
  216. uint16_t eDOP;
  217. };
  218. struct PACKED ubx_nav_solution {
  219. uint32_t itow;
  220. int32_t time_nsec;
  221. uint16_t week;
  222. uint8_t fix_type;
  223. uint8_t fix_status;
  224. int32_t ecef_x;
  225. int32_t ecef_y;
  226. int32_t ecef_z;
  227. uint32_t position_accuracy_3d;
  228. int32_t ecef_x_velocity;
  229. int32_t ecef_y_velocity;
  230. int32_t ecef_z_velocity;
  231. uint32_t speed_accuracy;
  232. uint16_t position_DOP;
  233. uint8_t res;
  234. uint8_t satellites;
  235. uint32_t res2;
  236. };
  237. struct PACKED ubx_nav_pvt {
  238. uint32_t itow;
  239. uint16_t year;
  240. uint8_t month, day, hour, min, sec;
  241. uint8_t valid;
  242. uint32_t t_acc;
  243. int32_t nano;
  244. uint8_t fix_type;
  245. uint8_t flags;
  246. uint8_t flags2;
  247. uint8_t num_sv;
  248. int32_t lon, lat;
  249. int32_t height, h_msl;
  250. uint32_t h_acc, v_acc;
  251. int32_t velN, velE, velD, gspeed;
  252. int32_t head_mot;
  253. uint32_t s_acc;
  254. uint32_t head_acc;
  255. uint16_t p_dop;
  256. uint8_t reserved1[6];
  257. uint32_t headVeh;
  258. uint8_t reserved2[4];
  259. };
  260. struct PACKED ubx_nav_velned {
  261. uint32_t itow; // GPS msToW
  262. int32_t ned_north;
  263. int32_t ned_east;
  264. int32_t ned_down;
  265. uint32_t speed_3d;
  266. uint32_t speed_2d;
  267. int32_t heading_2d;
  268. uint32_t speed_accuracy;
  269. uint32_t heading_accuracy;
  270. };
  271. struct PACKED ubx_nav_timegps {
  272. uint32_t itow;
  273. int32_t ftow;
  274. uint16_t week;
  275. int8_t leapS;
  276. uint8_t valid; // leapsvalid | weekvalid | tow valid;
  277. uint32_t tAcc;
  278. };
  279. // Lea6 uses a 60 byte message
  280. struct PACKED ubx_mon_hw_60 {
  281. uint32_t pinSel;
  282. uint32_t pinBank;
  283. uint32_t pinDir;
  284. uint32_t pinVal;
  285. uint16_t noisePerMS;
  286. uint16_t agcCnt;
  287. uint8_t aStatus;
  288. uint8_t aPower;
  289. uint8_t flags;
  290. uint8_t reserved1;
  291. uint32_t usedMask;
  292. uint8_t VP[17];
  293. uint8_t jamInd;
  294. uint16_t reserved3;
  295. uint32_t pinIrq;
  296. uint32_t pullH;
  297. uint32_t pullL;
  298. };
  299. // Neo7 uses a 68 byte message
  300. struct PACKED ubx_mon_hw_68 {
  301. uint32_t pinSel;
  302. uint32_t pinBank;
  303. uint32_t pinDir;
  304. uint32_t pinVal;
  305. uint16_t noisePerMS;
  306. uint16_t agcCnt;
  307. uint8_t aStatus;
  308. uint8_t aPower;
  309. uint8_t flags;
  310. uint8_t reserved1;
  311. uint32_t usedMask;
  312. uint8_t VP[25];
  313. uint8_t jamInd;
  314. uint16_t reserved3;
  315. uint32_t pinIrq;
  316. uint32_t pullH;
  317. uint32_t pullL;
  318. };
  319. struct PACKED ubx_mon_hw2 {
  320. int8_t ofsI;
  321. uint8_t magI;
  322. int8_t ofsQ;
  323. uint8_t magQ;
  324. uint8_t cfgSource;
  325. uint8_t reserved0[3];
  326. uint32_t lowLevCfg;
  327. uint32_t reserved1[2];
  328. uint32_t postStatus;
  329. uint32_t reserved2;
  330. };
  331. struct PACKED ubx_mon_ver {
  332. char swVersion[30];
  333. char hwVersion[10];
  334. char extension; // extensions are not enabled
  335. };
  336. struct PACKED ubx_nav_svinfo_header {
  337. uint32_t itow;
  338. uint8_t numCh;
  339. uint8_t globalFlags;
  340. uint16_t reserved;
  341. };
  342. #if UBLOX_RXM_RAW_LOGGING
  343. struct PACKED ubx_rxm_raw {
  344. int32_t iTOW;
  345. int16_t week;
  346. uint8_t numSV;
  347. uint8_t reserved1;
  348. struct ubx_rxm_raw_sv {
  349. double cpMes;
  350. double prMes;
  351. float doMes;
  352. uint8_t sv;
  353. int8_t mesQI;
  354. int8_t cno;
  355. uint8_t lli;
  356. } svinfo[UBLOX_MAX_RXM_RAW_SATS];
  357. };
  358. struct PACKED ubx_rxm_rawx {
  359. double rcvTow;
  360. uint16_t week;
  361. int8_t leapS;
  362. uint8_t numMeas;
  363. uint8_t recStat;
  364. uint8_t reserved1[3];
  365. PACKED struct ubx_rxm_rawx_sv {
  366. double prMes;
  367. double cpMes;
  368. float doMes;
  369. uint8_t gnssId;
  370. uint8_t svId;
  371. uint8_t reserved2;
  372. uint8_t freqId;
  373. uint16_t locktime;
  374. uint8_t cno;
  375. uint8_t prStdev;
  376. uint8_t cpStdev;
  377. uint8_t doStdev;
  378. uint8_t trkStat;
  379. uint8_t reserved3;
  380. } svinfo[UBLOX_MAX_RXM_RAWX_SATS];
  381. };
  382. #endif
  383. struct PACKED ubx_ack_ack {
  384. uint8_t clsID;
  385. uint8_t msgID;
  386. };
  387. struct PACKED ubx_cfg_cfg {
  388. uint32_t clearMask;
  389. uint32_t saveMask;
  390. uint32_t loadMask;
  391. };
  392. // Receive buffer
  393. union PACKED {
  394. DEFINE_BYTE_ARRAY_METHODS
  395. ubx_nav_posllh posllh;
  396. ubx_nav_status status;
  397. ubx_nav_dop dop;
  398. ubx_nav_solution solution;
  399. ubx_nav_pvt pvt;
  400. ubx_nav_timegps timegps;
  401. ubx_nav_velned velned;
  402. ubx_cfg_msg_rate msg_rate;
  403. ubx_cfg_msg_rate_6 msg_rate_6;
  404. ubx_cfg_nav_settings nav_settings;
  405. ubx_cfg_nav_rate nav_rate;
  406. ubx_cfg_prt prt;
  407. ubx_mon_hw_60 mon_hw_60;
  408. ubx_mon_hw_68 mon_hw_68;
  409. ubx_mon_hw2 mon_hw2;
  410. ubx_mon_ver mon_ver;
  411. ubx_cfg_tp5 nav_tp5;
  412. #if UBLOX_GNSS_SETTINGS
  413. ubx_cfg_gnss gnss;
  414. #endif
  415. ubx_cfg_sbas sbas;
  416. ubx_nav_svinfo_header svinfo_header;
  417. #if UBLOX_RXM_RAW_LOGGING
  418. ubx_rxm_raw rxm_raw;
  419. ubx_rxm_rawx rxm_rawx;
  420. #endif
  421. ubx_ack_ack ack;
  422. } _buffer;
  423. enum ubs_protocol_bytes {
  424. PREAMBLE1 = 0xb5,
  425. PREAMBLE2 = 0x62,
  426. CLASS_NAV = 0x01,
  427. CLASS_ACK = 0x05,
  428. CLASS_CFG = 0x06,
  429. CLASS_MON = 0x0A,
  430. CLASS_RXM = 0x02,
  431. MSG_ACK_NACK = 0x00,
  432. MSG_ACK_ACK = 0x01,
  433. MSG_POSLLH = 0x2,
  434. MSG_STATUS = 0x3,
  435. MSG_DOP = 0x4,
  436. MSG_SOL = 0x6,
  437. MSG_PVT = 0x7,
  438. MSG_TIMEGPS = 0x20,
  439. MSG_VELNED = 0x12,
  440. MSG_CFG_CFG = 0x09,
  441. MSG_CFG_RATE = 0x08,
  442. MSG_CFG_MSG = 0x01,
  443. MSG_CFG_NAV_SETTINGS = 0x24,
  444. MSG_CFG_PRT = 0x00,
  445. MSG_CFG_SBAS = 0x16,
  446. MSG_CFG_GNSS = 0x3E,
  447. MSG_CFG_TP5 = 0x31,
  448. MSG_MON_HW = 0x09,
  449. MSG_MON_HW2 = 0x0B,
  450. MSG_MON_VER = 0x04,
  451. MSG_NAV_SVINFO = 0x30,
  452. MSG_RXM_RAW = 0x10,
  453. MSG_RXM_RAWX = 0x15
  454. };
  455. enum ubx_gnss_identifier {
  456. GNSS_GPS = 0x00,
  457. GNSS_SBAS = 0x01,
  458. GNSS_GALILEO = 0x02,
  459. GNSS_BEIDOU = 0x03,
  460. GNSS_IMES = 0x04,
  461. GNSS_QZSS = 0x05,
  462. GNSS_GLONASS = 0x06
  463. };
  464. enum ubs_nav_fix_type {
  465. FIX_NONE = 0,
  466. FIX_DEAD_RECKONING = 1,
  467. FIX_2D = 2,
  468. FIX_3D = 3,
  469. FIX_GPS_DEAD_RECKONING = 4,
  470. FIX_TIME = 5
  471. };
  472. enum ubx_nav_status_bits {
  473. NAV_STATUS_FIX_VALID = 1,
  474. NAV_STATUS_DGPS_USED = 2
  475. };
  476. enum ubx_hardware_version {
  477. ANTARIS = 0,
  478. UBLOX_5,
  479. UBLOX_6,
  480. UBLOX_7,
  481. UBLOX_M8,
  482. UBLOX_F9 = 0x80, // comes from MON_VER hwVersion string
  483. UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
  484. // flagging state in the driver
  485. };
  486. enum config_step {
  487. STEP_PVT = 0,
  488. STEP_NAV_RATE, // poll NAV rate
  489. STEP_SOL,
  490. STEP_PORT,
  491. STEP_STATUS,
  492. STEP_POSLLH,
  493. STEP_VELNED,
  494. STEP_TIMEGPS,
  495. STEP_POLL_SVINFO, // poll svinfo
  496. STEP_POLL_SBAS, // poll SBAS
  497. STEP_POLL_NAV, // poll NAV settings
  498. STEP_POLL_GNSS, // poll GNSS
  499. STEP_POLL_TP5, // poll TP5
  500. STEP_DOP,
  501. STEP_MON_HW,
  502. STEP_MON_HW2,
  503. STEP_RAW,
  504. STEP_RAWX,
  505. STEP_VERSION,
  506. STEP_LAST
  507. };
  508. // Packet checksum accumulators
  509. uint8_t _ck_a;
  510. uint8_t _ck_b;
  511. // State machine state
  512. uint8_t _step;
  513. uint8_t _msg_id;
  514. uint16_t _payload_length;
  515. uint16_t _payload_counter;
  516. uint8_t _class;
  517. bool _cfg_saved;
  518. uint32_t _last_vel_time;
  519. uint32_t _last_pos_time;
  520. uint32_t _last_cfg_sent_time;
  521. uint8_t _num_cfg_save_tries;
  522. uint32_t _last_config_time;
  523. uint16_t _delay_time;
  524. uint8_t _next_message;
  525. uint8_t _ublox_port;
  526. bool _have_version;
  527. struct ubx_mon_ver _version;
  528. uint32_t _unconfigured_messages;
  529. uint8_t _hardware_generation;
  530. // do we have new position information?
  531. bool _new_position:1;
  532. // do we have new speed information?
  533. bool _new_speed:1;
  534. uint8_t _disable_counter;
  535. // Buffer parse & GPS state update
  536. bool _parse_gps();
  537. // used to update fix between status and position packets
  538. AP_GPS::GPS_Status next_fix;
  539. bool _cfg_needs_save;
  540. bool noReceivedHdop;
  541. bool havePvtMsg;
  542. bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
  543. void _configure_rate(void);
  544. void _configure_sbas(bool enable);
  545. void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);
  546. bool _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size);
  547. void send_next_rate_update(void);
  548. bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);
  549. void _request_next_config(void);
  550. void _request_port(void);
  551. void _request_version(void);
  552. void _save_cfg(void);
  553. void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
  554. void _check_new_itow(uint32_t itow);
  555. void unexpected_message(void);
  556. void log_mon_hw(void);
  557. void log_mon_hw2(void);
  558. void log_rxm_raw(const struct ubx_rxm_raw &raw);
  559. void log_rxm_rawx(const struct ubx_rxm_rawx &raw);
  560. // Calculates the correct log message ID based on what GPS instance is being logged
  561. uint8_t _ubx_msg_log_index(uint8_t ubx_msg) {
  562. return (uint8_t)(ubx_msg + (state.instance * UBX_MSG_TYPES));
  563. }
  564. };