ublox.h
Go to the documentation of this file.
1 #ifndef UBLOX_H
2 #define UBLOX_H
3 
4 #include "uart.h"
5 
6 #define UBLOX_BUFFER_SIZE 128
7 
8 
9 class UBLOX {
10 public:
11  enum {
14  FIX_TYPE_2D = 0x02,
15  FIX_TYPE_3D = 0x03,
18  };
19 
20  enum {
21  START_BYTE_1 = 0xB5,
22  START_BYTE_2 = 0x62,
23  };
24 
25  enum {
28  };
29 
30  enum {
31  CLASS_NAV = 0x01, // Navigation Results Messages: Position, Speed, Time, Acceleration, Heading, DOP, SVs used
32  CLASS_RXM = 0x02, // Receiver Manager Messages: Satellite Status, RTC Status
33  CLASS_INF = 0x04, // Information Messages: Printf-Style Messages, with IDs such as Error, Warning, Notice
34  CLASS_ACK = 0x05, // Ack/Nak Messages: Acknowledge or Reject messages to CFG input messages
35  CLASS_CFG = 0x06, // Configuration Input Messages: Set Dynamic Model, Set DOP Mask, Set Baud Rate, etc.
36  CLASS_UPD = 0x09, // Firmware Update Messages: Memory/Flash erase/write, Reboot, Flash identification, etc.
37  CLASS_MON = 0x0A, // Monitoring Messages: Communication Status, CPU Load, Stack Usage, Task Status
38  CLASS_AID = 0x0B, // AssistNow Aiding Messages: Ephemeris, Almanac, other A-GPS data input
39  CLASS_TIM = 0x0D, // Timing Messages: Time Pulse Output, Time Mark Results
40  CLASS_ESF = 0x10, // External Sensor Fusion Messages: External Sensor Measurements and Status Information
41  CLASS_MGA = 0x13, // Multiple GNSS Assistance Messages: Assistance data for various GNSS
42  CLASS_LOG = 0x21, // Logging Messages: Log creation, deletion, info and retrieva
43  };
44 
45  enum {
46  ACK_ACK = 0x01, // Message Acknowledged
47  ACK_NACK = 0x00, // Message Not-Acknowledged
48  };
49 
50  enum {
51  AID_ALM = 0x30, // Poll GPS Aiding Almanac Data
52  AID_AOP = 0x33, // AssistNow Autonomous data
53  AID_EPH = 0x31, // GPS Aiding Ephemeris Input/Output Message
54  AID_HUI = 0x02, // Poll GPS Health, UTC, ionosphere parameters
55  AID_INI = 0x01, // Aiding position, time, frequency, clock drift
56  };
57 
58  enum {
59  CFG_ANT = 0x13, // Get/Set Antenna Control Settings
60  CFG_BATCH = 0x93, // Get/Set Get/Set data batching configuration
61  CFG_CFG = 0x09, // Command Clear, Save and Load configurations
62  CFG_DAT = 0x06, // Get The currently defined Datum
63  CFG_DGNSS = 0x70, // Get/Set DGNSS configuration
64  CFG_DOSC = 0x61, // Get/Set Disciplined oscillator configuration
65  CFG_DYNSEED = 0x85, // Set Programming the dynamic seed for the host...
66  CFG_ESRC = 0x60, // Get/Set External synchronization source configuration
67  CFG_FIXSEED = 0x84, // Set Programming the fixed seed for host...
68  CFG_GEOFENCE = 0x69,// Get/Set Geofencing configuration
69  CFG_GNSS = 0x3E, // Get/Set GNSS system configuration
70  CFG_HNR = 0x5C, // Get/Set High Navigation Rate Settings
71  CFG_INF = 0x02, // Poll Request Poll configuration for one protocol
72  CFG_ITFM = 0x39, // Get/Set Jamming/Interference Monitor configuration
73  FG_LOGFILTER = 0x47,// Get/Set Data Logger Configuration
74  CFG_MSG = 0x01, // Poll Request Poll a message configuration
75  CFG_NAV5 = 0x24, // Get/Set Navigation Engine Settings
76  CFG_NAVX5 = 0x23, // Get/Set Navigation Engine Expert Settings
77  CFG_NMEA = 0x17, // Get/Set NMEA protocol configuration (deprecated)
78  CFG_ODO = 0x1E, // Get/Set Odometer, Low_speed COG Engine Settings
79  CFG_PM2 = 0x3B, // Get/Set Extended Power Management configuration
80  CFG_PMS = 0x86, // Get/Set Power Mode Setup
81  CFG_PRT = 0x00, // Poll Request Polls the configuration for one I/O Port
82  CFG_PWR = 0x57, // Set Put receiver in a defined power state.
83  CFG_RATE = 0x08, // Get/Set Navigation/Measurement Rate Settings
84  CFG_RINV = 0x34, // Get/Set Contents of Remote Inventory
85  CFG_RST = 0x04, // Command Reset Receiver / Clear Backup Data Structures
86  CFG_RXM = 0x11, // Get/Set RXM configuration
87  CFG_SBAS = 0x16, // Get/Set SBAS Configuration
88  CFG_SMGR = 0x62, // Get/Set Synchronization manager configuration
89  CFG_TMODE2 = 0x3D, // Get/Set Time Mode Settings 2
90  CFG_TMODE3 = 0x71, // Get/Set Time Mode Settings 3
91  CFG_TP5 = 0x31, // Poll Request Poll Time Pulse Parameters for Time Pulse 0
92  CFG_TXSLOT = 0x53, // Set TX buffer time slots configuration
93  CFG_USB = 0x1B, // Get/Set USB Configuration
94  };
95 
96  enum {
97  NAV_AOPSTATUS = 0x60, // Periodic/Polled AssistNow Autonomous Status
98  NAV_ATT = 0x05, // Periodic/Polled Attitude Solution
99  NAV_CLOCK = 0x22, // Periodic/Polled Clock Solution
100  NAV_DGPS = 0x31, // Periodic/Polled DGPS Data Used for NAV
101  NAV_DOP = 0x04, // Periodic/Polled Dilution of precision
102  NAV_EOE = 0x61, // Periodic End Of Epoch
103  NAV_GEOFENCE = 0x39, // Periodic/Polled Geofencing status
104  NAV_HPPOSECEF = 0x13, // Periodic/Polled High Precision Position Solution in ECEF
105  NAV_HPPOSLLH = 0x14, // Periodic/Polled High Precision Geodetic Position Solution
106  NAV_ODO = 0x09, // Periodic/Polled Odometer Solution
107  NAV_ORB = 0x34, // Periodic/Polled GNSS Orbit Database Info
108  NAV_POSECEF = 0x01, // Periodic/Polled Position Solution in ECEF
109  NAV_POSLLH = 0x02, // Periodic/Polled Geodetic Position Solution
110  NAV_PVT = 0x07, // Periodic/Polled Navigation Position Velocity Time Solution
111  NAV_RELPOSNED = 0x3C, // Periodic/Polled Relative Positioning Information in NED frame
112  NAV_RESETODO = 0x10, // Command Reset odometer
113  NAV_SAT = 0x35, // Periodic/Polled Satellite Information
114  NAV_SBAS = 0x32, // Periodic/Polled SBAS Status Data
115  NAV_SOL = 0x06, // Periodic/Polled Navigation Solution Information
116  NAV_STATUS = 0x03, // Periodic/Polled Receiver Navigation Status
117  NAV_SVINFO = 0x30, // Periodic/Polled Space Vehicle Information
118  NAV_SVIN = 0x3B, // Periodic/Polled Survey-in data
119  NAV_TIMEBDS = 0x24, // Periodic/Polled BDS Time Solution
120  NAV_TIMEGAL = 0x25, // Periodic/Polled Galileo Time Solution
121  NAV_TIMEGLO = 0x23, // Periodic/Polled GLO Time Solution
122  NAV_TIMEGPS = 0x20, // Periodic/Polled GPS Time Solution
123  NAV_TIMELS = 0x26, // Periodic/Polled Leap second event information
124  NAV_TIMEUTC = 0x21, // Periodic/Polled UTC Time Solution
125  NAV_VELECEF = 0x11, // Periodic/Polled Velocity Solution in ECEF
126  NAV_VELNED = 0x12, // Periodic/Polled Velocity Solution in NED
127  };
128 
129  typedef enum {
140  } parse_state_t;
141 
142  typedef struct {
143  uint8_t clsID;
144  uint8_t msgID;
145  }__attribute__((packed)) ACK_ACK_t;
146 
147  typedef struct {
148  uint8_t clsID;
149  uint8_t msgID;
150  }__attribute__((packed)) ACK_NACK_t;
151 
152  typedef struct {
153  uint8_t msgClass;
154  uint8_t msgID;
155  uint8_t rate;
156  }__attribute__((packed)) CFG_MSG_t;
157 
158  typedef struct {
159  enum {
160  DYNMODE_PORTABLE = 0,
161  DYNMODE_STATIONARY = 2,
162  DYNMODE_PEDESTRIAN = 3,
163  DYNMODE_AUTOMOTIVE = 4,
164  DYNMODE_SEA = 5,
165  DYNMODE_AIRBORNE_1G = 6,
166  DYNMODE_AIRBORNE_2G = 7,
167  DYNMODE_AIRBORNE_4G = 8
168  };
169  enum {
170  FIXMODE_2D_ONLY = 1,
171  FIXMODE_3D_ONLY = 2,
172  FIXMODE_AUTO = 3,
173  };
174 
175  enum{
176  UTC_STANDARD_AUTO = 0, // receiver selects based on GNSS configuration (see GNSS time bases).
177  UTC_STANDARD_USA = 3, // UTC as operated by the U.S. Naval Observatory (USNO); derived from GPS time
178  UTC_STANDARD_RUS = 6, // UTC as operated by the former Soviet Union; derived from GLONASS time
179  UTC_STANDARD_CHN = 7, // UTC as operated by the National Time Service Center, China; derived from BeiDou time
180  };
181 
182  enum {
183  MASK_DYN = 0x01, // Apply dynamic model settings
184  MASK_MINEL = 0x02, // Apply minimum elevation settings
185  MASK_POSFIXMODE = 0x04, // Apply fix mode settings
186  MASK_DRLIM = 0x08, // Reserved
187  MASK_POSMASK = 0x10, // Apply position mask settings
188  MASK_TIMEMASK = 0x20, // Apply time mask settings
189  MASK_STATICHOLDMASK = 0x40, // Apply static hold settings
190  MASK_DGPSMASK = 0x80, // Apply DGPS settings.
191  MASK_CNOTHRESHOLD = 0x100, // Apply CNO threshold settings (cnoThresh, cnoThreshNumSVs).
192  MASK_UTC = 0x200, // Apply UTC settings
193  };
194 
195  uint16_t mask;
196  uint8_t dynModel;
197  uint8_t fixMode;
198  int32_t fixedAlt; // (1e-2 m) Fixed altitude (mean sea level) for 2D fix mode.
199  uint32_t fixedAltVar; // (0.0001 m^2)Fixed altitude variance for 2D mode.
200  int8_t minElev; // (deg) Minimum Elevation for a GNSS satellite to be used in NAV
201  uint8_t drLimit; // s Reserved
202  uint16_t pDop; // (0.1) - Position DOP Mask to use
203  uint16_t tDop; // (0.1) - Time DOP Mask to use
204  uint16_t pAcc; // m Position Accuracy Mask
205  uint16_t tAcc; // m Time Accuracy Mask
206  uint8_t staticHoldThr; // esh cm/s Static hold threshold
207  uint8_t dgnssTimeout; // s DGNSS timeout
208  uint8_t cnoThreshNumS; // Vs - Number of satellites required to have C/N0 above cnoThresh for a fix to be attempted
209  uint8_t cnoThresh; // dBHz C/N0 threshold for deciding whether to attempt a fix
210  uint8_t reserved1[2]; // - Reserved
211  uint16_t staticHoldMax; // Dist m Static hold distance threshold (before quitting static hold)
212  uint8_t utcStandard; // - UTC standard to be used:
213  uint8_t reserved2[5];
214 
215  }__attribute__((packed)) CFG_NAV5_t;
216 
217  typedef struct {
218  enum {
219  PORT_I2C = 0,
220  PORT_UART1 = 1,
221  PORT_USB = 3,
222  PORT_SPI = 4
223  };
224  enum {
225  CHARLEN_8BIT = 0xC0,
226  PARITY_NONE = 0x800,
227  STOP_BITS_1 = 0x0000
228  };
229  enum {
230  IN_UBX = 0x01,
231  IN_NMEA = 0x02,
232  IN_RTCM = 0x04,
233  IN_RTCM3 = 0x20
234  };
235  enum {
236  OUT_UBX = 0x01,
237  OUT_NMEA = 0x02,
238  OUT_RTCM3 = 0x20,
239  };
240  uint8_t portID;
241  uint8_t reserved1;
242  uint16_t txReady;
243  uint32_t mode; // What the mode the serial data is on (See charlen, parity and stop bits)
244  uint32_t baudrate;
245  uint16_t inProtoMask; // Which input protocols are enabled
246  uint16_t outProtoMask; // Which output protocols are enabled
247  uint16_t flags;
248  uint8_t reserved2[2];
249  }__attribute__((packed)) CFG_PRT_t;
250 
251  typedef struct {
252  enum {
253  TIME_REF_UTC = 0,
254  TIME_REF_GPS = 1,
255  TIME_REF_GLONASS = 2,
256  TIME_REF_BUIDOU = 3,
257  TIME_REF_GALILEO = 4
258  };
259  uint16_t measRate; // (ms) The elapsed time between GNSS measurements which defines the rate
260  uint16_t navRate; // (cycles) The ratio between the number of measurements and the number of navigation solutions, e.g. 5 means five measurements for every navigation solution
261  uint16_t timeRef; // Time system to which measurements are aligned
262  }__attribute__((packed)) CFG_RATE_t;
263 
264  typedef struct {
265  enum {
266  VALIDITY_FLAGS_VALIDDATE= 0x01, // Valid UTC Date (see Time Validity section for details)
267  VALIDITY_FLAGS_VALIDTIME = 0x02, // Valid UTC Time of Day (see Time Validity section for details)
268  VALIDITY_FLAGS_FULLYRESOLVED = 0x04, // UTC Time of Day has been fully resolved (no seconds uncertainty)
269  };
270 
271  enum {
272  FIX_STATUS_PSM_STATE_NOT_ACTIVE = 0x00,
273  FIX_STATUS_GNSS_FIX_OK = 0x01, // Valid Fix
274  FIX_STATUS_DIFF_SOLN = 0x02, // Differential Corrections were applied
275  FIX_STATUS_PSM_STATE_ENABLED = 0x04,
276  FIX_STATUS_PSM_STATE_ACQUISITION = 0x08,
277  FIX_STATUS_PSM_STATE_TRACKING = 0x12,
278  FIX_STATUS_PSM_STATE_POWER_OPTIMIZED_TRACKING = 0x10,
279  FIX_STATUS_PSM_STATE_INACTIVE = 0x14,
280  FIX_STATUS_HEADING_VALID = 0x20,
281  FIX_STATUS_CARR_SOLN_NONE = 0x00,
282  FIX_STATUS_CARR_SOLN_FLOAT = 0x40,
283  FIX_STATUS_CARR_SOLN_FIXED = 0x80,
284  };
285 
286  uint32_t iTOW; // ms GPS time of week of the navigation epoch . See the description of iTOW for details.
287  uint16_t year; // y Year (UTC)
288  uint8_t month; // month Month, range 1..12 (UTC)
289  uint8_t day; // d Day of month, range 1..31 (UTC)
290  uint8_t hour; // h Hour of day, range 0..23 (UTC)
291  uint8_t min; // min Minute of hour, range 0..59 (UTC)
292  uint8_t sec; // s Seconds of minute, range 0..60 (UTC)
293  uint8_t valid; // - Validity flags (see graphic below )
294  uint32_t tAcc; // ns Time accuracy estimate (UTC)
295  int32_t nano; // ns Fraction of second, range -1e9 .. 1e9 (UTC)
296  uint8_t fixType; // - GNSSfix Type:
297  uint8_t flags; // - Fix status flags (see graphic below )
298  uint8_t flags2; // - Additional flags (see graphic below )
299  uint8_t numSV; // - Number of satellites used in Nav Solution
300  int32_t lon; // 1e-7 deg Longitude
301  int32_t lat; // 1e-7 deg Latitude
302  int32_t height; // mm Height above ellipsoid
303  int32_t hMSL; // mm Height above mean sea level
304  uint32_t hAcc; // mm Horizontal accuracy estimate
305  uint32_t vAcc; // mm Vertical accuracy estimate
306  int32_t velN; // mm/s NED north velocity
307  int32_t velE; // mm/s NED east velocity
308  int32_t velD; // mm/s NED down velocity
309  int32_t gSpeed; // mm/s Ground Speed (2-D)
310  int32_t headMot; // 1e-5 deg Heading of motion (2-D)
311  uint32_t sAcc; // mm/s Speed accuracy estimate
312  uint32_t headAcc; // 1e-5 deg Heading accuracy estimate (both motion and vehicle)
313  uint16_t pDOP; // 0.01 - Position DOP
314  uint8_t reserved1; //[6] - Reserved
315  int32_t headVeh; // 1e-5 deg Heading of vehicle (2-D)
316  int16_t magDec; // 1e-2 deg Magnetic declination
317  uint16_t magAcc; // 1e-2 deg Magnetic declination accuracy
318  }__attribute__((packed)) NAV_PVT_t;
319 
320  typedef struct
321  {
322  uint32_t iTOW;
323  int32_t ecefX;
324  int32_t ecefY;
325  int32_t ecefZ;
326  uint32_t pAcc;
327  }__attribute__((packed)) NAV_POSECEF_t;
328 
329  typedef struct
330  {
331  uint32_t iTOW;
332  int32_t ecefVX;
333  int32_t ecefVY;
334  int32_t ecefVZ;
335  uint32_t sAcc;
336  }__attribute__((packed)) NAV_VELECEF_t;
337 
338  typedef union {
340  ACK_ACK_t ACK_ACK;
341  ACK_NACK_t ACK_NACK;
342  CFG_MSG_t CFG_MSG;
343  CFG_PRT_t CFG_PRT;
344  CFG_RATE_t CFG_RATE;
345  CFG_NAV5_t CFG_NAV5;
346  NAV_PVT_t NAV_PVT;
347  NAV_POSECEF_t NAV_POSECEF;
348  NAV_VELECEF_t NAV_VELECEF;
349  } UBX_message_t;
350 
351  void init(UART* uart_drv);
352 
353  void read_cb(uint8_t byte);
354  inline bool new_data() { return new_data_; }
355  inline uint32_t num_messages_received() { return num_messages_received_; }
356  inline const NAV_PVT_t& get_nav_data() const { return nav_message_; }
357  void get_pos_ecef(double* pos_ecef, uint32_t* t_ms);
358  void get_vel_ecef(float* vel_ecef, uint32_t* t_ms);
359  void read(double* lla, float* vel, uint8_t* fix_type, uint32_t* t_ms);
360 
361 private:
362  void convert_data();
363  void enable_message(uint8_t msg_cls, uint8_t msg_id, uint8_t rate);
364  void set_baudrate(const uint32_t baudrate);
365  void set_dynamic_mode();
366  void set_nav_rate(uint8_t period_ms);
367  bool decode_message();
368  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;
369  bool send_message(uint8_t msg_class, uint8_t msg_id, UBX_message_t& message, uint16_t len);
370 
371  uint32_t current_baudrate_ = 115200;
372  const uint32_t baudrates[5] = {115200, 57600, 9600, 19200, 38400};
373 
376 
377  char debug_buffer_[15];
378  uint16_t debug_buffer_head_ = 0;
379 
380  uint16_t buffer_head_ = 0;
381  bool got_message_ = false;
382  bool got_ack_ = false;
383  bool got_nack_ = false;
384  parse_state_t parse_state_;
385  uint8_t message_class_;
386  uint8_t message_type_;
387  uint16_t length_;
388  uint8_t ck_a_;
389  uint8_t ck_b_;
390  uint32_t num_errors_ = 0;
392 
393  double lla_[3];
394  float vel_[3];
395 
397  uint8_t prev_byte_ = 0;
398 
400 
401  bool new_data_;
403  NAV_PVT_t nav_message_;
404  NAV_POSECEF_t pos_ecef_message_;
405  NAV_VELECEF_t vel_ecef_message_;
406 };
407 
408 #endif // UBLOX_H
CFG_NAV5_t CFG_NAV5
Definition: ublox.h:345
#define UBLOX_BUFFER_SIZE
Definition: ublox.h:6
uint16_t flags
Definition: ublox.h:247
int16_t magDec
Definition: ublox.h:316
bool got_ack_
Definition: ublox.h:382
void set_dynamic_mode()
Definition: ublox.cpp:98
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:333
uint8_t utcStandard
Definition: ublox.h:212
void set_baudrate(const uint32_t baudrate)
Definition: ublox.cpp:83
NAV_POSECEF_t NAV_POSECEF
Definition: ublox.h:347
uint8_t ck_a_
Definition: ublox.h:388
uint16_t pDop
Definition: ublox.h:202
bool got_message_
Definition: ublox.h:381
uint8_t ck_b_
Definition: ublox.h:389
uint16_t tAcc
Definition: ublox.h:205
uint32_t mode
Definition: ublox.h:243
int32_t ecefVX
Definition: ublox.h:332
uint32_t num_errors_
Definition: ublox.h:390
uint8_t msgClass
Definition: ublox.h:153
void get_vel_ecef(float *vel_ecef, uint32_t *t_ms)
Definition: ublox.cpp:230
Definition: ublox.h:9
uint8_t prev_byte_
Definition: ublox.h:397
void enable_message(uint8_t msg_cls, uint8_t msg_id, uint8_t rate)
Definition: ublox.cpp:115
bool looking_for_nmea_
Definition: ublox.h:396
uint16_t length_
Definition: ublox.h:387
uint16_t staticHoldMax
Definition: ublox.h:211
int32_t gSpeed
Definition: ublox.h:309
float vel_[3]
Definition: ublox.h:394
static uint8_t buffer[BMP280_DATA_FRAME_SIZE]
Definition: drv_bmp280.c:61
uint16_t navRate
Definition: ublox.h:260
UBX_message_t out_message_
Definition: ublox.h:374
uint8_t dgnssTimeout
Definition: ublox.h:207
NAV_PVT_t NAV_PVT
Definition: ublox.h:346
bool new_data_
Definition: ublox.h:401
bool decode_message()
Definition: ublox.cpp:254
uint16_t buffer_head_
Definition: ublox.h:380
parse_state_t parse_state_
Definition: ublox.h:384
uint32_t pAcc
Definition: ublox.h:326
uint8_t drLimit
Definition: ublox.h:201
int32_t system_start_tow_ms_
Definition: ublox.h:402
uint32_t iTOW
Definition: ublox.h:286
CFG_RATE_t CFG_RATE
Definition: ublox.h:344
uint32_t num_messages_received()
Definition: ublox.h:355
NAV_POSECEF_t pos_ecef_message_
Definition: ublox.h:404
uint32_t fixedAltVar
Definition: ublox.h:199
int32_t ecefVY
Definition: ublox.h:333
uint8_t dynModel
Definition: ublox.h:196
uint8_t message_type_
Definition: ublox.h:386
uint32_t headAcc
Definition: ublox.h:312
uint32_t hAcc
Definition: ublox.h:304
uint16_t mask
Definition: ublox.h:195
uint16_t year
Definition: ublox.h:287
NAV_VELECEF_t vel_ecef_message_
Definition: ublox.h:405
uint8_t message_class_
Definition: ublox.h:385
uint32_t current_baudrate_
Definition: ublox.h:371
uint32_t sAcc
Definition: ublox.h:311
uint8_t portID
Definition: ublox.h:240
uint16_t measRate
Definition: ublox.h:259
bool send_message(uint8_t msg_class, uint8_t msg_id, UBX_message_t &message, uint16_t len)
Definition: ublox.cpp:62
char debug_buffer_[15]
Definition: ublox.h:377
Definition: uart.h:43
void set_nav_rate(uint8_t period_ms)
Definition: ublox.cpp:106
void get_pos_ecef(double *pos_ecef, uint32_t *t_ms)
Definition: ublox.cpp:222
uint8_t fixType
Definition: ublox.h:296
uint16_t magAcc
Definition: ublox.h:317
const NAV_PVT_t & get_nav_data() const
Definition: ublox.h:356
int32_t headVeh
Definition: ublox.h:315
double lla_[3]
Definition: ublox.h:393
uint16_t pDOP
Definition: ublox.h:313
uint8_t staticHoldThr
Definition: ublox.h:206
uint16_t outProtoMask
Definition: ublox.h:246
uint16_t tDop
Definition: ublox.h:203
bool got_nack_
Definition: ublox.h:383
bool new_data()
Definition: ublox.h:354
ACK_NACK_t ACK_NACK
Definition: ublox.h:341
NAV_VELECEF_t NAV_VELECEF
Definition: ublox.h:348
void init(UART *uart_drv)
Definition: ublox.cpp:12
uint32_t num_messages_received_
Definition: ublox.h:391
uint16_t inProtoMask
Definition: ublox.h:245
uint16_t pAcc
Definition: ublox.h:204
const uint32_t baudrates[5]
Definition: ublox.h:372
uint8_t flags2
Definition: ublox.h:298
struct __attribute__((packed))
Definition: usbd_cdc_vcp.h:66
uint8_t cnoThreshNumS
Definition: ublox.h:208
int32_t fixedAlt
Definition: ublox.h:198
void read_cb(uint8_t byte)
Definition: ublox.cpp:125
uint16_t debug_buffer_head_
Definition: ublox.h:378
int32_t ecefVZ
Definition: ublox.h:334
uint32_t tAcc
Definition: ublox.h:294
CFG_MSG_t CFG_MSG
Definition: ublox.h:342
uint8_t cnoThresh
Definition: ublox.h:209
int32_t height
Definition: ublox.h:302
uint16_t txReady
Definition: ublox.h:242
parse_state_t
Definition: ublox.h:129
CFG_PRT_t CFG_PRT
Definition: ublox.h:343
int32_t headMot
Definition: ublox.h:310
uint32_t baudrate
Definition: ublox.h:244
ACK_ACK_t ACK_ACK
Definition: ublox.h:340
UBX_message_t in_message_
Definition: ublox.h:375
NAV_PVT_t nav_message_
Definition: ublox.h:403
uint8_t fixMode
Definition: ublox.h:197
void convert_data()
Definition: ublox.cpp:321
void read(double *lla, float *vel, uint8_t *fix_type, uint32_t *t_ms)
Definition: ublox.cpp:238
UART * serial_
Definition: ublox.h:399
uint16_t timeRef
Definition: ublox.h:261
uint32_t vAcc
Definition: ublox.h:305


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Oct 24 2019 03:17:20