ublox.h
Go to the documentation of this file.
1 #ifndef UBLOX_H
2 #define UBLOX_H
3 
4 #define UBLOX_BUFFER_SIZE 128
5 
6 #include "uart.h"
7 
8 #include <stdint.h>
9 
10 #include <iostream>
11 #include <string>
12 #include <vector>
13 
14 class UBLOX
15 {
16 public:
17  UBLOX();
18  // The majority of the enums and structs below were auto generated from the documentation
19  enum FixType // Fix types
20  {
23  FIX_TYPE_2D = 0x02,
24  FIX_TYPE_3D = 0x03,
27  };
28 
29  enum // Start Bytes
30  {
31  START_BYTE_1 = 0xB5,
32  START_BYTE_2 = 0x62,
33  };
34 
35  enum // NMEA Start Bytes
36  {
39  };
40 
41  enum // Message Classes
42  {
43  CLASS_NAV = 0x01, // Navigation Results Messages: Position, Speed, Time, Acceleration, Heading, DOP, SVs used
44  CLASS_RXM = 0x02, // Receiver Manager Messages: Satellite Status, RTC Status
45  CLASS_INF = 0x04, // Information Messages: Printf-Style Messages, with IDs such as Error, Warning, Notice
46  CLASS_ACK = 0x05, // Ack/Nak Messages: Acknowledge or Reject messages to CFG input messages
47  CLASS_CFG = 0x06, // Configuration Input Messages: Set Dynamic Model, Set DOP Mask, Set Baud Rate, etc.
48  CLASS_UPD = 0x09, // Firmware Update Messages: Memory/Flash erase/write, Reboot, Flash identification, etc.
49  CLASS_MON = 0x0A, // Monitoring Messages: Communication Status, CPU Load, Stack Usage, Task Status
50  CLASS_AID = 0x0B, // AssistNow Aiding Messages: Ephemeris, Almanac, other A-GPS data input
51  CLASS_TIM = 0x0D, // Timing Messages: Time Pulse Output, Time Mark Results
52  CLASS_ESF = 0x10, // External Sensor Fusion Messages: External Sensor Measurements and Status Information
53  CLASS_MGA = 0x13, // Multiple GNSS Assistance Messages: Assistance data for various GNSS
54  CLASS_LOG = 0x21, // Logging Messages: Log creation, deletion, info and retrieva
55  };
56 
57  enum // Ack/Nack
58  {
59  ACK_ACK = 0x01, // Message Acknowledged
60  ACK_NACK = 0x00, // Message Not-Acknowledged
61  };
62 
63  enum // AID enums
64  {
65  AID_ALM = 0x30, // Poll GPS Aiding Almanac Data
66  AID_AOP = 0x33, // AssistNow Autonomous data
67  AID_EPH = 0x31, // GPS Aiding Ephemeris Input/Output Message
68  AID_HUI = 0x02, // Poll GPS Health, UTC, ionosphere parameters
69  AID_INI = 0x01, // Aiding position, time, frequency, clock drift
70  };
71 
72  enum // CFG Message ID's
73  {
74  CFG_ANT = 0x13, // Get/Set Antenna Control Settings
75  CFG_BATCH = 0x93, // Get/Set Get/Set data batching configuration
76  CFG_CFG = 0x09, // Command Clear, Save and Load configurations
77  CFG_DAT = 0x06, // Get The currently defined Datum
78  CFG_DGNSS = 0x70, // Get/Set DGNSS configuration
79  CFG_DOSC = 0x61, // Get/Set Disciplined oscillator configuration
80  CFG_DYNSEED = 0x85, // Set Programming the dynamic seed for the host...
81  CFG_ESRC = 0x60, // Get/Set External synchronization source configuration
82  CFG_FIXSEED = 0x84, // Set Programming the fixed seed for host...
83  CFG_GEOFENCE = 0x69, // Get/Set Geofencing configuration
84  CFG_GNSS = 0x3E, // Get/Set GNSS system configuration
85  CFG_HNR = 0x5C, // Get/Set High Navigation Rate Settings
86  CFG_INF = 0x02, // Poll Request Poll configuration for one protocol
87  CFG_ITFM = 0x39, // Get/Set Jamming/Interference Monitor configuration
88  CFG_LOGFILTER = 0x47, // Get/Set Data Logger Configuration
89  CFG_MSG = 0x01, // Poll Request Poll a message configuration
90  CFG_NAV5 = 0x24, // Get/Set Navigation Engine Settings
91  CFG_NAVX5 = 0x23, // Get/Set Navigation Engine Expert Settings
92  CFG_NMEA = 0x17, // Get/Set NMEA protocol configuration (deprecated)
93  CFG_ODO = 0x1E, // Get/Set Odometer, Low_speed COG Engine Settings
94  CFG_PM2 = 0x3B, // Get/Set Extended Power Management configuration
95  CFG_PMS = 0x86, // Get/Set Power Mode Setup
96  CFG_PRT = 0x00, // Poll Request Polls the configuration for one I/O Port
97  CFG_PWR = 0x57, // Set Put receiver in a defined power state.
98  CFG_RATE = 0x08, // Get/Set Navigation/Measurement Rate Settings
99  CFG_RINV = 0x34, // Get/Set Contents of Remote Inventory
100  CFG_RST = 0x04, // Command Reset Receiver / Clear Backup Data Structures
101  CFG_RXM = 0x11, // Get/Set RXM configuration
102  CFG_SBAS = 0x16, // Get/Set SBAS Configuration
103  CFG_SMGR = 0x62, // Get/Set Synchronization manager configuration
104  CFG_TMODE2 = 0x3D, // Get/Set Time Mode Settings 2
105  CFG_TMODE3 = 0x71, // Get/Set Time Mode Settings 3
106  CFG_TP5 = 0x31, // Poll Request Poll Time Pulse Parameters for Time Pulse 0
107  CFG_TXSLOT = 0x53, // Set TX buffer time slots configuration
108  CFG_USB = 0x1B, // Get/Set USB Configuration
109  };
110 
111  enum // NAV Message ID's
112  {
113  NAV_AOPSTATUS = 0x60, // Periodic/Polled AssistNow Autonomous Status
114  NAV_ATT = 0x05, // Periodic/Polled Attitude Solution
115  NAV_CLOCK = 0x22, // Periodic/Polled Clock Solution
116  NAV_DGPS = 0x31, // Periodic/Polled DGPS Data Used for NAV
117  NAV_DOP = 0x04, // Periodic/Polled Dilution of precision
118  NAV_EOE = 0x61, // Periodic End Of Epoch
119  NAV_GEOFENCE = 0x39, // Periodic/Polled Geofencing status
120  NAV_HPPOSECEF = 0x13, // Periodic/Polled High Precision Position Solution in ECEF
121  NAV_HPPOSLLH = 0x14, // Periodic/Polled High Precision Geodetic Position Solution
122  NAV_ODO = 0x09, // Periodic/Polled Odometer Solution
123  NAV_ORB = 0x34, // Periodic/Polled GNSS Orbit Database Info
124  NAV_POSECEF = 0x01, // Periodic/Polled Position Solution in ECEF
125  NAV_POSLLH = 0x02, // Periodic/Polled Geodetic Position Solution
126  NAV_PVT = 0x07, // Periodic/Polled Navigation Position Velocity Time Solution
127  NAV_RELPOSNED = 0x3C, // Periodic/Polled Relative Positioning Information in NED frame
128  NAV_RESETODO = 0x10, // Command Reset odometer
129  NAV_SAT = 0x35, // Periodic/Polled Satellite Information
130  NAV_SBAS = 0x32, // Periodic/Polled SBAS Status Data
131  NAV_SOL = 0x06, // Periodic/Polled Navigation Solution Information
132  NAV_STATUS = 0x03, // Periodic/Polled Receiver Navigation Status
133  NAV_SVINFO = 0x30, // Periodic/Polled Space Vehicle Information
134  NAV_SVIN = 0x3B, // Periodic/Polled Survey-in data
135  NAV_TIMEBDS = 0x24, // Periodic/Polled BDS Time Solution
136  NAV_TIMEGAL = 0x25, // Periodic/Polled Galileo Time Solution
137  NAV_TIMEGLO = 0x23, // Periodic/Polled GLO Time Solution
138  NAV_TIMEGPS = 0x20, // Periodic/Polled GPS Time Solution
139  NAV_TIMELS = 0x26, // Periodic/Polled Leap second event information
140  NAV_TIMEUTC = 0x21, // Periodic/Polled UTC Time Solution
141  NAV_VELECEF = 0x11, // Periodic/Polled Velocity Solution in ECEF
142  NAV_VELNED = 0x12, // Periodic/Polled Velocity Solution in NED
143  };
144 
145  typedef enum // State machine states
146  {
157  } parse_state_t;
158 
159  typedef struct
160  {
161  uint8_t clsID;
162  uint8_t msgID;
163  } __attribute__((packed)) ACK_ACK_t;
164 
165  typedef struct
166  {
167  uint8_t clsID;
168  uint8_t msgID;
169  } __attribute__((packed)) ACK_NACK_t;
170 
171  typedef struct
172  {
173  uint8_t msgClass;
174  uint8_t msgID;
175  uint8_t rate;
176  } __attribute__((packed)) CFG_MSG_t;
177 
178  typedef struct // Navigation settings, for CFG NAV5 command
179  {
180  enum // DYNMODE options
181  {
182  DYNMODE_PORTABLE = 0,
183  DYNMODE_STATIONARY = 2,
184  DYNMODE_PEDESTRIAN = 3,
185  DYNMODE_AUTOMOTIVE = 4,
186  DYNMODE_SEA = 5,
187  DYNMODE_AIRBORNE_1G = 6,
188  DYNMODE_AIRBORNE_2G = 7,
189  DYNMODE_AIRBORNE_4G = 8
190  };
191  enum // FIXMODE options
192  {
193  FIXMODE_2D_ONLY = 1,
194  FIXMODE_3D_ONLY = 2,
195  FIXMODE_AUTO = 3,
196  };
197 
198  enum // UTC options
199  {
200  UTC_STANDARD_AUTO = 0, // receiver selects based on GNSS configuration (see GNSS time bases).
201  UTC_STANDARD_USA = 3, // UTC as operated by the U.S. Naval Observatory (USNO); derived from GPS time
202  UTC_STANDARD_RUS = 6, // UTC as operated by the former Soviet Union; derived from GLONASS time
203  UTC_STANDARD_CHN = 7, // UTC as operated by the National Time Service Center, China; derived from BeiDou time
204  };
205 
206  enum // MASK options
207  {
208  MASK_DYN = 0x001, // Apply dynamic model settings
209  MASK_MINEL = 0x002, // Apply minimum elevation settings
210  MASK_POSFIXMODE = 0x004, // Apply fix mode settings
211  MASK_DRLIM = 0x008, // Reserved
212  MASK_POSMASK = 0x010, // Apply position mask settings
213  MASK_TIMEMASK = 0x020, // Apply time mask settings
214  MASK_STATICHOLDMASK = 0x040, // Apply static hold settings
215  MASK_DGPSMASK = 0x080, // Apply DGPS settings.
216  MASK_CNOTHRESHOLD = 0x100, // Apply CNO threshold settings (cnoThresh, cnoThreshNumSVs).
217  MASK_UTC = 0x200, // Apply UTC settings
218  };
219 
220  uint16_t mask;
221  uint8_t dynModel;
222  uint8_t fixMode;
223  int32_t fixedAlt; // (1e-2 m) Fixed altitude (mean sea level) for 2D fix mode.
224  uint32_t fixedAltVar; // (0.0001 m^2)Fixed altitude variance for 2D mode.
225  int8_t minElev; // (deg) Minimum Elevation for a GNSS satellite to be used in NAV
226  uint8_t drLimit; // s Reserved
227  uint16_t pDop; // (0.1) - Position DOP Mask to use
228  uint16_t tDop; // (0.1) - Time DOP Mask to use
229  uint16_t pAcc; // m Position Accuracy Mask
230  uint16_t tAcc; // m Time Accuracy Mask
231  uint8_t staticHoldThr; // esh cm/s Static hold threshold
232  uint8_t dgnssTimeout; // s DGNSS timeout
233  uint8_t cnoThreshNumS; // Vs - Number of satellites required to have C/N0 above cnoThresh for a fix to be attempted
234  uint8_t cnoThresh; // dBHz C/N0 threshold for deciding whether to attempt a fix
235  uint8_t reserved1[2]; // - Reserved
236  uint16_t staticHoldMax; // Dist m Static hold distance threshold (before quitting static hold)
237  uint8_t utcStandard; // - UTC standard to be used:
238  uint8_t reserved2[5];
239 
240  } __attribute__((packed)) CFG_NAV5_t;
241 
242  typedef struct // Port settings, for CFG PRT command
243  {
244  enum // Serial Port choice
245  {
246  PORT_I2C = 0,
247  PORT_UART1 = 1,
248  PORT_USB = 3,
249  PORT_SPI = 4
250  };
251  enum // UART settings
252  {
253  CHARLEN_8BIT = 0x00C0,
254  PARITY_NONE = 0x0800,
255  STOP_BITS_1 = 0x0000
256  };
257  enum // In Protocol choice
258  {
259  IN_UBX = 0x01,
260  IN_NMEA = 0x02,
261  IN_RTCM = 0x04,
262  IN_RTCM3 = 0x20,
263  };
264  enum // Out Protocal choice
265  {
266  OUT_UBX = 0x01,
267  OUT_NMEA = 0x02,
268  OUT_RTCM3 = 0x20,
269  };
270  uint8_t portID;
271  uint8_t reserved1;
272  uint16_t txReady;
273  uint32_t mode; // What the mode the serial data is on (See charlen, parity and stop bits)
274  uint32_t baudrate;
275  uint16_t inProtoMask; // Which input protocols are enabled
276  uint16_t outProtoMask; // Which output protocols are enabled
277  uint16_t flags;
278  uint8_t reserved2[2];
279  } __attribute__((packed)) CFG_PRT_t;
280 
281  typedef struct // Ouput rate settings, for CFG RATE command
282  {
283  enum // Time Reference choice
284  {
285  TIME_REF_UTC = 0,
286  TIME_REF_GPS = 1,
287  TIME_REF_GLONASS = 2,
288  TIME_REF_BUIDOU = 3,
289  TIME_REF_GALILEO = 4
290  };
291  uint16_t measRate; // (ms) The elapsed time between GNSS measurements which defines the rate
292  uint16_t navRate; // (cycles) The ratio between the number of measurements and the number of navigation solutions,
293  // e.g. 5 means five measurements for every navigation solution
294  uint16_t timeRef; // Time system to which measurements are aligned
295  } __attribute__((packed)) CFG_RATE_t;
296 
297  // Time data is pulled into a separate struct for ease of use
298  typedef struct
299  {
300  uint16_t year; // y Year (UTC)
301  uint8_t month; // month Month, range 1..12 (UTC)
302  uint8_t day; // d Day of month, range 1..31 (UTC)
303  uint8_t hour; // h Hour of day, range 0..23 (UTC)
304  uint8_t min; // min Minute of hour, range 0..59 (UTC)
305  uint8_t sec; // s Seconds of minute, range 0..60 (UTC)
306  uint8_t valid; // - Validity flags (see graphic below )
307  uint32_t tAcc; // ns Time accuracy estimate (UTC)
308  int32_t nano; // ns Fraction of second, range -1e9 .. 1e9 (UTC)
309  } __attribute__((packed)) GNSS_TIME_T;
310  typedef struct // Position, velocity, time packet NAV PVT
311  {
312  enum // Time validity flags
313  {
314  VALIDITY_FLAGS_VALIDDATE = 0x01, // Valid UTC Date (see Time Validity section for details)
315  VALIDITY_FLAGS_VALIDTIME = 0x02, // Valid UTC Time of Day (see Time Validity section for details)
316  VALIDITY_FLAGS_FULLYRESOLVED = 0x04, // UTC Time of Day has been fully resolved (no seconds uncertainty)
317  };
318 
319  enum // Flags from the "flags" field
320  {
321  FIX_STATUS_GNSS_FIX_OK = 0x01, // Valid Fix
322  FIX_STATUS_DIFF_SOLN = 0x02, // Differential Corrections were applied
323  FIX_STATUS_PSM_STATE_NOT_ACTIVE = 0x00,
324  FIX_STATUS_PSM_STATE_ENABLED = 0x04,
325  FIX_STATUS_PSM_STATE_ACQUISITION = 0x08,
326  FIX_STATUS_PSM_STATE_TRACKING = 0x0C,
327  FIX_STATUS_PSM_STATE_POWER_OPTIMIZED_TRACKING = 0x10,
328  FIX_STATUS_PSM_STATE_INACTIVE = 0x14,
329  FIX_STATUS_HEADING_VALID = 0x20,
330  FIX_STATUS_CARR_SOLN_NONE = 0x00,
331  FIX_STATUS_CARR_SOLN_FLOAT = 0x40,
332  FIX_STATUS_CARR_SOLN_FIXED = 0x80,
333  };
334 
335  uint32_t iTOW; // ms GPS time of week of the navigation epoch . See the description of iTOW for details.
336  GNSS_TIME_T time; // Pulled out into a struct for easier use
337  uint8_t fixType; // - GNSSfix Type:
338  uint8_t flags; // - Fix status flags (see graphic below )
339  uint8_t flags2; // - Additional flags (see graphic below )
340  uint8_t numSV; // - Number of satellites used in Nav Solution
341  int32_t lon; // 1e-7 deg Longitude
342  int32_t lat; // 1e-7 deg Latitude
343  int32_t height; // mm Height above ellipsoid
344  int32_t hMSL; // mm Height above mean sea level
345  uint32_t hAcc; // mm Horizontal accuracy estimate
346  uint32_t vAcc; // mm Vertical accuracy estimate
347  int32_t velN; // mm/s NED north velocity
348  int32_t velE; // mm/s NED east velocity
349  int32_t velD; // mm/s NED down velocity
350  int32_t gSpeed; // mm/s Ground Speed (2-D)
351  int32_t headMot; // 1e-5 deg Heading of motion (2-D)
352  uint32_t sAcc; // mm/s Speed accuracy estimate
353  uint32_t headAcc; // 1e-5 deg Heading accuracy estimate (both motion and vehicle)
354  uint16_t pDOP; // 0.01 - Position DOP
355  uint8_t reserved1; //[6] - Reserved
356  int32_t headVeh; // 1e-5 deg Heading of vehicle (2-D)
357  int16_t magDec; // 1e-2 deg Magnetic declination
358  uint16_t magAcc; // 1e-2 deg Magnetic declination accuracy
359  } __attribute__((packed)) NAV_PVT_t;
360 
361  // This struct is manually generatated, and meant to allow easier conversions
362  typedef struct
363  {
364  uint16_t year; // y Year (UTC)
365  uint8_t month; // month Month, range 1..12 (UTC)
366  uint8_t day; // d Day of month, range 1..31 (UTC)
367  uint8_t hour; // h Hour of day, range 0..23 (UTC)
368  uint8_t min; // min Minute of hour, range 0..59 (UTC)
369  uint8_t sec; // s Seconds of minute, range 0..60 (UTC)
370  int32_t nano; // ns Fraction of second, range -1e9 .. 1e9 (UTC)
371  } UTCTime;
372 
373  typedef struct // Earth centered, earth fixed position data
374  {
375  uint32_t iTOW; // ms GPS time of week of the navigation epoch . See the description of iTOW for details.
376  int32_t ecefX; // cm ECEF X coordinate
377  int32_t ecefY; // cm ECEF Y coordinate
378  int32_t ecefZ; // cm ECEF Z coordinate
379  uint32_t pAcc; // cm Position Accuracy Estimate
380  } __attribute__((packed)) NAV_POSECEF_t;
381 
382  typedef struct // Earth centered, earth fixed velocity data
383  {
384  uint32_t iTOW; // ms GPS time of week of the navigation epoch . See the description of iTOW for details.
385  int32_t ecefVX; // cm ECEF X velocity
386  int32_t ecefVY; // cm ECEF Y velocity
387  int32_t ecefVZ; // cm ECEF Z velocity
388  uint32_t sAcc; // cm Speed Accuracy Estimate
389  } __attribute__((packed)) NAV_VELECEF_t;
390 
391  typedef union // A union of all of the message data payloads, to allow for reinterpretation
392  {
394  ACK_ACK_t ACK_ACK;
395  ACK_NACK_t ACK_NACK;
396  CFG_MSG_t CFG_MSG;
397  CFG_PRT_t CFG_PRT;
398  CFG_RATE_t CFG_RATE;
399  CFG_NAV5_t CFG_NAV5;
400  NAV_PVT_t NAV_PVT;
401  NAV_POSECEF_t NAV_POSECEF;
402  NAV_VELECEF_t NAV_VELECEF;
403  } UBX_message_t;
404 
405  struct GNSSPVT
406  {
407  uint32_t time_of_week;
409  uint64_t time;
410  int32_t nanos; // There is a chance for this to be negative
411  int32_t lat;
412  int32_t lon;
413  int32_t height;
414  int32_t vel_n;
415  int32_t vel_e;
416  int32_t vel_d;
417  uint32_t h_acc;
418  uint32_t v_acc;
420  };
421 
422  // The following structs are used as return values
423  struct GNSSPosECEF
424  {
425  uint32_t time_of_week; // time of week. Only to be used as a stamp
426  int32_t x; // cm
427  int32_t y; // cm
428  int32_t z; // cm
429  uint32_t p_acc; // cm
430  };
431 
432  struct GNSSVelECEF
433  {
434  uint32_t time_of_week; // time of week. Only to be used as a stamp
435  int32_t vx; // cm/s
436  int32_t vy; // cm/s
437  int32_t vz; // cm/s
438  uint32_t s_acc; // cm/s
439  };
440 
441  static constexpr uint32_t BAUD_RATE{115200};
443 
444  void init(UART *uart);
446 
447  bool present();
448  bool new_data(); // Returns true if new data has been recieved, AND the time of week stamps on all of the data
449  // matches
450  GNSSPVT read();
453  const NAV_PVT_t &read_full();
454  void read_ecef(int32_t *pos_ecef, int32_t *vel_ecef, uint32_t &p_acc_ecef, uint32_t &s_acc_ecef);
455  void read_cb(uint8_t byte);
457 
458  inline uint64_t get_last_pvt_timestamp() { return last_pvt_timestamp_; }
459 
460 private:
463  void finish_init();
464  void enable_message(uint8_t msg_cls, uint8_t msg_id, uint8_t rate);
465  void set_baudrate(const uint32_t baudrate);
466  void set_dynamic_mode();
467  void set_nav_rate(uint8_t period_ms);
468  bool decode_message();
469  void calculate_checksum(const uint8_t msg_cls,
470  const uint8_t msg_id,
471  const uint16_t len,
472  const UBX_message_t &payload,
473  uint8_t &ck_a,
474  uint8_t &ck_b) const;
475  bool send_ubx_message(uint8_t msg_class, uint8_t msg_id, UBX_message_t &message, uint16_t len);
476 
477  bool is_initialized_{false};
478 
480  static constexpr size_t BAUDRATE_SEARCH_COUNT{5};
481  static constexpr uint32_t BAUDRATE_SEARCH_TIME_MS{1000};
482  const uint32_t baudrates[BAUDRATE_SEARCH_COUNT] = {115200, 19200, 57600, 9600, 38400};
483  bool searching_baudrate_{false};
486 
487  uint32_t last_valid_message_{0};
488  static constexpr uint32_t TIMEOUT_MS{5000};
489 
492 
493  uint16_t buffer_head_ = 0;
494  bool got_message_ = false;
495  bool got_ack_ = false;
496  bool got_nack_ = false;
497  parse_state_t parse_state_;
498  uint8_t message_class_;
499  uint8_t message_type_;
500  uint16_t length_;
501  uint8_t ck_a_;
502  uint8_t ck_b_;
503  uint32_t num_errors_ = 0;
504  volatile uint32_t num_messages_received_ = 0;
505 
506  uint64_t last_pvt_timestamp_ = 0;
507  uint64_t time_ = 0;
508 
509  bool looking_for_nmea_ = true;
510  uint8_t prev_byte_ = 0;
511 
512  UART *serial_ = nullptr;
513 
514  volatile bool new_data_ = false;
515 #pragma GCC diagnostic push
516 #pragma GCC diagnostic ignored "-Wmissing-field-initializers"
517  NAV_PVT_t nav_message_ = {};
518  NAV_POSECEF_t pos_ecef_ = {};
519  NAV_VELECEF_t vel_ecef_ = {};
520 #pragma GCC diagnostic pop
521 };
522 
523 const std::string fix_names[6] = {
524  "FIX_TYPE_NO_FIX", "FIX_TYPE_DEAD_RECKONING", "FIX_TYPE_2D",
525  "FIX_TYPE_3D", "FIX_TYPE_GPS_AND_DEAD_RECKONING", "FIX_TYPE_TIME_ONLY",
526 };
527 
528 #endif // UBLOX_H
uint32_t time_of_week
Definition: ublox.h:434
uint64_t time_
Definition: ublox.h:507
CFG_NAV5_t CFG_NAV5
Definition: ublox.h:399
void read_ecef(int32_t *pos_ecef, int32_t *vel_ecef, uint32_t &p_acc_ecef, uint32_t &s_acc_ecef)
#define UBLOX_BUFFER_SIZE
Definition: ublox.h:4
uint16_t flags
Definition: ublox.h:277
int16_t magDec
Definition: ublox.h:357
bool got_ack_
Definition: ublox.h:495
FixType
Definition: ublox.h:19
int32_t vel_e
Definition: ublox.h:415
void set_dynamic_mode()
Definition: ublox.cpp:139
uint64_t get_last_pvt_timestamp()
Definition: ublox.h:458
uint8_t utcStandard
Definition: ublox.h:237
void set_baudrate(const uint32_t baudrate)
Definition: ublox.cpp:112
volatile uint32_t num_messages_received_
Definition: ublox.h:504
bool is_initialized_
Definition: ublox.h:477
NAV_POSECEF_t NAV_POSECEF
Definition: ublox.h:401
uint8_t ck_a_
Definition: ublox.h:501
uint16_t pDop
Definition: ublox.h:227
bool got_message_
Definition: ublox.h:494
uint8_t ck_b_
Definition: ublox.h:502
void increment_detect_baudrate_async()
Definition: ublox.cpp:61
uint32_t time_of_week
Definition: ublox.h:407
uint16_t tAcc
Definition: ublox.h:230
uint32_t mode
Definition: ublox.h:273
int32_t ecefVX
Definition: ublox.h:385
static constexpr uint32_t BAUD_RATE
Definition: ublox.h:441
uint32_t num_errors_
Definition: ublox.h:503
uint8_t msgClass
Definition: ublox.h:173
Definition: ublox.h:14
uint8_t min
Definition: ublox.h:368
uint8_t prev_byte_
Definition: ublox.h:510
UBLOX()
Definition: ublox.cpp:13
void enable_message(uint8_t msg_cls, uint8_t msg_id, uint8_t rate)
Definition: ublox.cpp:158
int32_t vy
Definition: ublox.h:436
bool looking_for_nmea_
Definition: ublox.h:509
int32_t nanos
Definition: ublox.h:410
uint64_t rosflight_timestamp
Definition: ublox.h:419
uint16_t length_
Definition: ublox.h:500
uint16_t staticHoldMax
Definition: ublox.h:236
int32_t gSpeed
Definition: ublox.h:350
static uint8_t buffer[BMP280_DATA_FRAME_SIZE]
Definition: drv_bmp280.c:61
uint16_t navRate
Definition: ublox.h:292
int32_t nano
Definition: ublox.h:370
uint32_t last_baudrate_change_ms_
Definition: ublox.h:485
NAV_VELECEF_t vel_ecef_
Definition: ublox.h:519
UBX_message_t out_message_
Definition: ublox.h:490
uint8_t dgnssTimeout
Definition: ublox.h:232
uart_mode_t
Definition: uart.h:45
uint32_t s_acc
Definition: ublox.h:438
NAV_PVT_t NAV_PVT
Definition: ublox.h:400
uint8_t hour
Definition: ublox.h:367
size_t baudrate_search_index_
Definition: ublox.h:484
volatile bool new_data_
Definition: ublox.h:514
bool decode_message()
Definition: ublox.cpp:327
static constexpr uint32_t TIMEOUT_MS
Definition: ublox.h:488
void init(UART *uart)
Definition: ublox.cpp:16
uint16_t buffer_head_
Definition: ublox.h:493
parse_state_t parse_state_
Definition: ublox.h:497
uint32_t pAcc
Definition: ublox.h:379
static constexpr UART::uart_mode_t UART_MODE
Definition: ublox.h:442
uint8_t drLimit
Definition: ublox.h:226
FixType fix_type
Definition: ublox.h:408
uint32_t iTOW
Definition: ublox.h:335
CFG_RATE_t CFG_RATE
Definition: ublox.h:398
uint32_t num_messages_received()
Definition: ublox.h:456
void calculate_checksum(const uint8_t msg_cls, const uint8_t msg_id, const uint16_t len, const UBX_message_t &payload, uint8_t &ck_a, uint8_t &ck_b) const
Definition: ublox.cpp:387
uint32_t fixedAltVar
Definition: ublox.h:224
int32_t ecefVY
Definition: ublox.h:386
uint8_t dynModel
Definition: ublox.h:221
uint8_t message_type_
Definition: ublox.h:499
uint32_t headAcc
Definition: ublox.h:353
uint64_t time
Definition: ublox.h:409
const std::string fix_names[6]
Definition: ublox.h:523
bool searching_baudrate_
Definition: ublox.h:483
uint32_t hAcc
Definition: ublox.h:345
uint16_t mask
Definition: ublox.h:220
uint16_t year
Definition: ublox.h:300
uint8_t sec
Definition: ublox.h:369
uint8_t message_class_
Definition: ublox.h:498
uint32_t current_baudrate_
Definition: ublox.h:479
uint32_t sAcc
Definition: ublox.h:352
int32_t height
Definition: ublox.h:413
uint32_t p_acc
Definition: ublox.h:429
int32_t lat
Definition: ublox.h:411
uint8_t portID
Definition: ublox.h:270
int32_t vx
Definition: ublox.h:435
uint16_t measRate
Definition: ublox.h:291
Definition: uart.h:42
void set_nav_rate(uint8_t period_ms)
Definition: ublox.cpp:148
void start_detect_baudrate_async()
Definition: ublox.cpp:55
bool send_ubx_message(uint8_t msg_class, uint8_t msg_id, UBX_message_t &message, uint16_t len)
Definition: ublox.cpp:90
uint8_t fixType
Definition: ublox.h:337
uint16_t magAcc
Definition: ublox.h:358
int32_t lon
Definition: ublox.h:412
GNSS_TIME_T time
Definition: ublox.h:336
int32_t headVeh
Definition: ublox.h:356
uint16_t pDOP
Definition: ublox.h:354
uint32_t last_valid_message_
Definition: ublox.h:487
uint8_t staticHoldThr
Definition: ublox.h:231
static constexpr uint32_t BAUDRATE_SEARCH_TIME_MS
Definition: ublox.h:481
uint16_t outProtoMask
Definition: ublox.h:276
uint32_t time_of_week
Definition: ublox.h:425
uint16_t tDop
Definition: ublox.h:228
uint32_t v_acc
Definition: ublox.h:418
bool got_nack_
Definition: ublox.h:496
bool new_data()
Definition: ublox.cpp:286
int32_t vel_d
Definition: ublox.h:416
bool present()
Definition: ublox.cpp:133
ACK_NACK_t ACK_NACK
Definition: ublox.h:395
NAV_VELECEF_t NAV_VELECEF
Definition: ublox.h:402
GNSSPosECEF read_pos_ecef()
Definition: ublox.cpp:310
uint8_t month
Definition: ublox.h:365
uint16_t inProtoMask
Definition: ublox.h:275
uint16_t pAcc
Definition: ublox.h:229
uint16_t year
Definition: ublox.h:364
uint8_t flags2
Definition: ublox.h:339
int32_t vel_n
Definition: ublox.h:414
uint8_t day
Definition: ublox.h:366
struct __attribute__((packed))
Definition: usbd_cdc_vcp.h:66
uint8_t cnoThreshNumS
Definition: ublox.h:233
int32_t fixedAlt
Definition: ublox.h:223
uint32_t h_acc
Definition: ublox.h:417
const NAV_PVT_t & read_full()
Definition: ublox.cpp:322
void read_cb(uint8_t byte)
Definition: ublox.cpp:167
int32_t ecefVZ
Definition: ublox.h:387
uint32_t tAcc
Definition: ublox.h:307
CFG_MSG_t CFG_MSG
Definition: ublox.h:396
uint8_t cnoThresh
Definition: ublox.h:234
int32_t height
Definition: ublox.h:343
void finish_init()
Definition: ublox.cpp:38
uint16_t txReady
Definition: ublox.h:272
GNSSVelECEF read_vel_ecef()
Definition: ublox.cpp:316
void check_connection_status()
Definition: ublox.cpp:71
parse_state_t
Definition: ublox.h:145
static constexpr size_t BAUDRATE_SEARCH_COUNT
Definition: ublox.h:480
uint64_t last_pvt_timestamp_
Definition: ublox.h:506
CFG_PRT_t CFG_PRT
Definition: ublox.h:397
NAV_POSECEF_t pos_ecef_
Definition: ublox.h:518
int32_t headMot
Definition: ublox.h:351
uint32_t baudrate
Definition: ublox.h:274
int32_t vz
Definition: ublox.h:437
const uint32_t baudrates[BAUDRATE_SEARCH_COUNT]
Definition: ublox.h:482
ACK_ACK_t ACK_ACK
Definition: ublox.h:394
UBX_message_t in_message_
Definition: ublox.h:491
NAV_PVT_t nav_message_
Definition: ublox.h:517
uint8_t fixMode
Definition: ublox.h:222
UART * serial_
Definition: ublox.h:512
uint16_t timeRef
Definition: ublox.h:294
uint32_t vAcc
Definition: ublox.h:346
GNSSPVT read()
Definition: ublox.cpp:291


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:49