Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS_UBLOX.h
9810 views
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
// u-blox UBX GPS driver for ArduPilot and ArduPilotMega.
18
// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
19
//
20
// UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
21
#pragma once
22
23
#include "AP_GPS_config.h"
24
25
#if AP_GPS_UBLOX_ENABLED
26
27
#include "AP_GPS.h"
28
#include "GPS_Backend.h"
29
30
#include <AP_HAL/AP_HAL.h>
31
32
/*
33
* try to put a UBlox into binary mode. This is in two parts.
34
*
35
* First we send a ubx binary message that enables the NAV_SOL message
36
* at rate 1. Then we send a NMEA message to set the baud rate to our
37
* desired rate. The reason for doing the NMEA message second is if we
38
* send it first the second message will be ignored for a baud rate
39
* change.
40
* The reason we need the NAV_SOL rate message at all is some uBlox
41
* modules are configured with all ubx binary messages off, which
42
* would mean we would never detect it.
43
44
* running a uBlox at less than 38400 will lead to packet
45
* corruption, as we can't receive the packets in the 200ms
46
* window for 5Hz fixes. The NMEA startup message should force
47
* the uBlox into 230400 no matter what rate it is configured
48
* for.
49
*/
50
#define UBLOX_SET_BINARY_115200 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n"
51
52
// a variant with 230400 baudrate
53
#define UBLOX_SET_BINARY_230400 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,230400,0*1E\r\n"
54
55
// a variant with 460800 baudrate
56
#define UBLOX_SET_BINARY_460800 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,460800,0*11\r\n"
57
58
#define UBLOX_RXM_RAW_LOGGING 1
59
#define UBLOX_MAX_RXM_RAW_SATS 22
60
#define UBLOX_MAX_RXM_RAWX_SATS 32
61
#define UBLOX_MAX_EXTENSIONS 8
62
#define UBLOX_GNSS_SETTINGS 1
63
#ifndef UBLOX_TIM_TM2_LOGGING
64
#define UBLOX_TIM_TM2_LOGGING (HAL_PROGRAM_SIZE_LIMIT_KB>1024)
65
#endif
66
67
#define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7
68
69
#define UBX_TIMEGPS_VALID_WEEK_MASK 0x2
70
71
#define UBLOX_MAX_PORTS 6
72
#define UBLOX_MODULE_LEN 9
73
74
#define RATE_POSLLH 1
75
#define RATE_STATUS 1
76
#define RATE_SOL 1
77
#define RATE_TIMEGPS 5
78
#define RATE_PVT 1
79
#define RATE_VELNED 1
80
#define RATE_DOP 1
81
#define RATE_HW 5
82
#define RATE_HW2 5
83
#define RATE_TIM_TM2 1
84
85
#define CONFIG_RATE_NAV (1<<0)
86
#define CONFIG_RATE_POSLLH (1<<1)
87
#define CONFIG_RATE_STATUS (1<<2)
88
#define CONFIG_RATE_SOL (1<<3)
89
#define CONFIG_RATE_VELNED (1<<4)
90
#define CONFIG_RATE_DOP (1<<5)
91
#define CONFIG_RATE_MON_HW (1<<6)
92
#define CONFIG_RATE_MON_HW2 (1<<7)
93
#define CONFIG_RATE_RAW (1<<8)
94
#define CONFIG_VERSION (1<<9)
95
#define CONFIG_NAV_SETTINGS (1<<10)
96
#define CONFIG_GNSS (1<<11)
97
#define CONFIG_SBAS (1<<12)
98
#define CONFIG_RATE_PVT (1<<13)
99
#define CONFIG_TP5 (1<<14)
100
#define CONFIG_RATE_TIMEGPS (1<<15)
101
#define CONFIG_TMODE_MODE (1<<16)
102
#define CONFIG_RTK_MOVBASE (1<<17)
103
#define CONFIG_TIM_TM2 (1<<18)
104
#define CONFIG_F9 (1<<19)
105
#define CONFIG_M10 (1<<20)
106
#define CONFIG_L5 (1<<21)
107
#define CONFIG_LAST (1<<22) // this must always be the last bit
108
109
#define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED)
110
111
#define CONFIG_ALL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_SOL | CONFIG_RATE_VELNED \
112
| CONFIG_RATE_DOP | CONFIG_RATE_MON_HW | CONFIG_RATE_MON_HW2 | CONFIG_RATE_RAW | CONFIG_VERSION \
113
| CONFIG_NAV_SETTINGS | CONFIG_GNSS | CONFIG_SBAS)
114
115
//Configuration Sub-Sections
116
#define SAVE_CFG_IO (1<<0)
117
#define SAVE_CFG_MSG (1<<1)
118
#define SAVE_CFG_INF (1<<2)
119
#define SAVE_CFG_NAV (1<<3)
120
#define SAVE_CFG_RXM (1<<4)
121
#define SAVE_CFG_RINV (1<<9)
122
#define SAVE_CFG_ANT (1<<10)
123
#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)
124
125
#define START_OF_WEEK_THRESHOLD_MS (60UL * AP_MSEC_PER_SEC)
126
#define END_OF_WEEK_THRESHOLD_MS AP_MSEC_PER_WEEK - START_OF_WEEK_THRESHOLD_MS
127
128
class RTCM3_Parser;
129
130
class AP_GPS_UBLOX : public AP_GPS_Backend
131
{
132
public:
133
AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port, AP_GPS::GPS_Role role);
134
~AP_GPS_UBLOX() override;
135
136
// Methods
137
bool read() override;
138
139
AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
140
141
static bool _detect(struct UBLOX_detect_state &state, uint8_t data);
142
143
bool is_configured(void) const override {
144
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
145
if (!gps._auto_config) {
146
return true;
147
} else {
148
return !_unconfigured_messages;
149
}
150
#else
151
return true;
152
#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
153
}
154
155
bool get_error_codes(uint32_t &error_codes) const override {
156
error_codes = _unconfigured_messages;
157
return true;
158
};
159
160
void broadcast_configuration_failure_reason(void) const override;
161
#if HAL_LOGGING_ENABLED
162
void Write_AP_Logger_Log_Startup_messages() const override;
163
#endif
164
165
// get the velocity lag, returns true if the driver is confident in the returned value
166
bool get_lag(float &lag_sec) const override;
167
168
const char *name() const override { return "u-blox"; }
169
170
// support for retrieving RTCMv3 data from a moving baseline base
171
bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len) override;
172
void clear_RTCMV3(void) override;
173
174
// ublox specific healthy checks
175
bool is_healthy(void) const override;
176
177
private:
178
// u-blox UBX protocol essentials
179
struct PACKED ubx_header {
180
uint8_t preamble1;
181
uint8_t preamble2;
182
uint8_t msg_class;
183
uint8_t msg_id;
184
uint16_t length;
185
};
186
#if UBLOX_GNSS_SETTINGS
187
struct PACKED ubx_cfg_gnss {
188
uint8_t msgVer;
189
uint8_t numTrkChHw;
190
uint8_t numTrkChUse;
191
uint8_t numConfigBlocks;
192
PACKED struct configBlock {
193
uint8_t gnssId;
194
uint8_t resTrkCh;
195
uint8_t maxTrkCh;
196
uint8_t reserved1;
197
uint32_t flags;
198
} configBlock[UBLOX_MAX_GNSS_CONFIG_BLOCKS];
199
};
200
#endif
201
struct PACKED ubx_cfg_nav_rate {
202
uint16_t measure_rate_ms;
203
uint16_t nav_rate;
204
uint16_t timeref;
205
};
206
struct PACKED ubx_cfg_msg {
207
uint8_t msg_class;
208
uint8_t msg_id;
209
};
210
struct PACKED ubx_cfg_msg_rate {
211
uint8_t msg_class;
212
uint8_t msg_id;
213
uint8_t rate;
214
};
215
struct PACKED ubx_cfg_msg_rate_6 {
216
uint8_t msg_class;
217
uint8_t msg_id;
218
uint8_t rates[6];
219
};
220
struct PACKED ubx_cfg_nav_settings {
221
uint16_t mask;
222
uint8_t dynModel;
223
uint8_t fixMode;
224
int32_t fixedAlt;
225
uint32_t fixedAltVar;
226
int8_t minElev;
227
uint8_t drLimit;
228
uint16_t pDop;
229
uint16_t tDop;
230
uint16_t pAcc;
231
uint16_t tAcc;
232
uint8_t staticHoldThresh;
233
uint8_t res1;
234
uint32_t res2;
235
uint32_t res3;
236
uint32_t res4;
237
};
238
struct PACKED ubx_cfg_tp5 {
239
uint8_t tpIdx;
240
uint8_t version;
241
uint8_t reserved1[2];
242
int16_t antCableDelay;
243
int16_t rfGroupDelay;
244
uint32_t freqPeriod;
245
uint32_t freqPeriodLock;
246
uint32_t pulseLenRatio;
247
uint32_t pulseLenRatioLock;
248
int32_t userConfigDelay;
249
uint32_t flags;
250
};
251
struct PACKED ubx_cfg_prt {
252
uint8_t portID;
253
};
254
struct PACKED ubx_cfg_sbas {
255
uint8_t mode;
256
uint8_t usage;
257
uint8_t maxSBAS;
258
uint8_t scanmode2;
259
uint32_t scanmode1;
260
};
261
// F9 config keys
262
enum class ConfigKey : uint32_t {
263
TMODE_MODE = 0x20030001,
264
CFG_RATE_MEAS = 0x30210001,
265
266
CFG_UART1_BAUDRATE = 0x40520001,
267
CFG_UART1_ENABLED = 0x10520005,
268
CFG_UART1INPROT_UBX = 0x10730001,
269
CFG_UART1INPROT_NMEA = 0x10730002,
270
CFG_UART1INPROT_RTCM3X = 0x10730004,
271
CFG_UART1OUTPROT_UBX = 0x10740001,
272
CFG_UART1OUTPROT_NMEA = 0x10740002,
273
CFG_UART1OUTPROT_RTCM3X = 0x10740004,
274
275
CFG_UART2_BAUDRATE = 0x40530001,
276
CFG_UART2_ENABLED = 0x10530005,
277
CFG_UART2INPROT_UBX = 0x10750001,
278
CFG_UART2INPROT_NMEA = 0x10750002,
279
CFG_UART2INPROT_RTCM3X = 0x10750004,
280
CFG_UART2OUTPROT_UBX = 0x10760001,
281
CFG_UART2OUTPROT_NMEA = 0x10760002,
282
CFG_UART2OUTPROT_RTCM3X = 0x10760004,
283
284
MSGOUT_RTCM_3X_TYPE4072_0_UART1 = 0x209102ff,
285
MSGOUT_RTCM_3X_TYPE4072_1_UART1 = 0x20910382,
286
MSGOUT_RTCM_3X_TYPE1077_UART1 = 0x209102cd,
287
MSGOUT_RTCM_3X_TYPE1087_UART1 = 0x209102d2,
288
MSGOUT_RTCM_3X_TYPE1097_UART1 = 0x20910319,
289
MSGOUT_RTCM_3X_TYPE1127_UART1 = 0x209102d7,
290
MSGOUT_RTCM_3X_TYPE1230_UART1 = 0x20910304,
291
MSGOUT_UBX_NAV_RELPOSNED_UART1 = 0x2091008e,
292
293
MSGOUT_RTCM_3X_TYPE4072_0_UART2 = 0x20910300,
294
MSGOUT_RTCM_3X_TYPE4072_1_UART2 = 0x20910383,
295
MSGOUT_RTCM_3X_TYPE1077_UART2 = 0x209102ce,
296
MSGOUT_RTCM_3X_TYPE1087_UART2 = 0x209102d3,
297
MSGOUT_RTCM_3X_TYPE1097_UART2 = 0x2091031a,
298
MSGOUT_RTCM_3X_TYPE1127_UART2 = 0x209102d8,
299
MSGOUT_RTCM_3X_TYPE1230_UART2 = 0x20910305,
300
MSGOUT_UBX_NAV_RELPOSNED_UART2 = 0x2091008f,
301
302
// enable specific signals and constellations
303
CFG_SIGNAL_GPS_ENA = 0x1031001f,
304
CFG_SIGNAL_GPS_L1CA_ENA = 0x10310001,
305
CFG_SIGNAL_GPS_L2C_ENA = 0x10310003,
306
CFG_SIGNAL_GPS_L5_ENA = 0x10310004,
307
CFG_SIGNAL_SBAS_ENA = 0x10310020,
308
CFG_SIGNAL_SBAS_L1CA_ENA = 0x10310005,
309
CFG_SIGNAL_GAL_ENA = 0x10310021,
310
CFG_SIGNAL_GAL_E1_ENA = 0x10310007,
311
CFG_SIGNAL_GAL_E5A_ENA = 0x10310009,
312
CFG_SIGNAL_GAL_E5B_ENA = 0x1031000a,
313
CFG_SIGNAL_BDS_ENA = 0x10310022,
314
CFG_SIGNAL_BDS_B1_ENA = 0x1031000d,
315
CFG_SIGNAL_BDS_B1C_ENA = 0x1031000f,
316
CFG_SIGNAL_BDS_B2_ENA = 0x1031000e,
317
CFG_SIGNAL_BDS_B2A_ENA = 0x10310028,
318
CFG_SIGNAL_QZSS_ENA = 0x10310024,
319
CFG_SIGNAL_QZSS_L1CA_ENA = 0x10310012,
320
CFG_SIGNAL_QZSS_L1S_ENA = 0x10310014,
321
CFG_SIGNAL_QZSS_L2C_ENA = 0x10310015,
322
CFG_SIGNAL_QZSS_L5_ENA = 0x10310017,
323
CFG_SIGNAL_GLO_ENA = 0x10310025,
324
CFG_SIGNAL_GLO_L1_ENA = 0x10310018,
325
CFG_SIGNAL_GLO_L2_ENA = 0x1031001a,
326
CFG_SIGNAL_NAVIC_ENA = 0x10310026,
327
CFG_SIGNAL_NAVIC_L5_ENA = 0x1031001d,
328
329
CFG_SIGNAL_L5_HEALTH_OVRD = 0x10320001,
330
331
// other keys
332
CFG_NAVSPG_DYNMODEL = 0x20110021,
333
334
};
335
336
// layers for VALSET
337
#define UBX_VALSET_LAYER_RAM 0x1U
338
#define UBX_VALSET_LAYER_BBR 0x2U
339
#define UBX_VALSET_LAYER_FLASH 0x4U
340
#define UBX_VALSET_LAYER_ALL 0x7U
341
342
struct PACKED ubx_cfg_valset {
343
uint8_t version;
344
uint8_t layers;
345
uint8_t transaction;
346
uint8_t reserved[1];
347
uint32_t key;
348
};
349
struct PACKED ubx_cfg_valget {
350
uint8_t version;
351
uint8_t layers;
352
uint8_t reserved[2];
353
// variable length data, check buffer length
354
};
355
struct PACKED ubx_nav_posllh {
356
uint32_t itow; // GPS msToW
357
int32_t longitude;
358
int32_t latitude;
359
int32_t altitude_ellipsoid;
360
int32_t altitude_msl;
361
uint32_t horizontal_accuracy;
362
uint32_t vertical_accuracy;
363
};
364
struct PACKED ubx_nav_status {
365
uint32_t itow; // GPS msToW
366
uint8_t fix_type;
367
uint8_t fix_status;
368
uint8_t differential_status;
369
uint8_t res;
370
uint32_t time_to_first_fix;
371
uint32_t uptime; // milliseconds
372
};
373
struct PACKED ubx_nav_dop {
374
uint32_t itow; // GPS msToW
375
uint16_t gDOP;
376
uint16_t pDOP;
377
uint16_t tDOP;
378
uint16_t vDOP;
379
uint16_t hDOP;
380
uint16_t nDOP;
381
uint16_t eDOP;
382
};
383
struct PACKED ubx_nav_solution {
384
uint32_t itow;
385
int32_t time_nsec;
386
uint16_t week;
387
uint8_t fix_type;
388
uint8_t fix_status;
389
int32_t ecef_x;
390
int32_t ecef_y;
391
int32_t ecef_z;
392
uint32_t position_accuracy_3d;
393
int32_t ecef_x_velocity;
394
int32_t ecef_y_velocity;
395
int32_t ecef_z_velocity;
396
uint32_t speed_accuracy;
397
uint16_t position_DOP;
398
uint8_t res;
399
uint8_t satellites;
400
uint32_t res2;
401
};
402
struct PACKED ubx_nav_pvt {
403
uint32_t itow;
404
uint16_t year;
405
uint8_t month, day, hour, min, sec;
406
uint8_t valid;
407
uint32_t t_acc;
408
int32_t nano;
409
uint8_t fix_type;
410
uint8_t flags;
411
uint8_t flags2;
412
uint8_t num_sv;
413
int32_t lon, lat;
414
int32_t h_ellipsoid, h_msl;
415
uint32_t h_acc, v_acc;
416
int32_t velN, velE, velD, gspeed;
417
int32_t head_mot;
418
uint32_t s_acc;
419
uint32_t head_acc;
420
uint16_t p_dop;
421
uint8_t flags3;
422
uint8_t reserved1[5];
423
int32_t headVeh;
424
int16_t magDec;
425
uint16_t magAcc;
426
};
427
struct PACKED ubx_nav_relposned {
428
uint8_t version;
429
uint8_t reserved1;
430
uint16_t refStationId;
431
uint32_t iTOW;
432
int32_t relPosN;
433
int32_t relPosE;
434
int32_t relPosD;
435
int32_t relPosLength;
436
int32_t relPosHeading;
437
uint8_t reserved2[4];
438
int8_t relPosHPN;
439
int8_t relPosHPE;
440
int8_t relPosHPD;
441
int8_t relPosHPLength;
442
uint32_t accN;
443
uint32_t accE;
444
uint32_t accD;
445
uint32_t accLength;
446
uint32_t accHeading;
447
uint8_t reserved3[4];
448
uint32_t flags;
449
};
450
451
struct PACKED ubx_nav_velned {
452
uint32_t itow; // GPS msToW
453
int32_t ned_north;
454
int32_t ned_east;
455
int32_t ned_down;
456
uint32_t speed_3d;
457
uint32_t speed_2d;
458
int32_t heading_2d;
459
uint32_t speed_accuracy;
460
uint32_t heading_accuracy;
461
};
462
463
struct PACKED ubx_nav_timegps {
464
uint32_t itow;
465
int32_t ftow;
466
uint16_t week;
467
int8_t leapS;
468
uint8_t valid; // leapsvalid | weekvalid | tow valid;
469
uint32_t tAcc;
470
};
471
472
// Lea6 uses a 60 byte message
473
struct PACKED ubx_mon_hw_60 {
474
uint32_t pinSel;
475
uint32_t pinBank;
476
uint32_t pinDir;
477
uint32_t pinVal;
478
uint16_t noisePerMS;
479
uint16_t agcCnt;
480
uint8_t aStatus;
481
uint8_t aPower;
482
uint8_t flags;
483
uint8_t reserved1;
484
uint32_t usedMask;
485
uint8_t VP[17];
486
uint8_t jamInd;
487
uint16_t reserved3;
488
uint32_t pinIrq;
489
uint32_t pullH;
490
uint32_t pullL;
491
};
492
// Neo7 uses a 68 byte message
493
struct PACKED ubx_mon_hw_68 {
494
uint32_t pinSel;
495
uint32_t pinBank;
496
uint32_t pinDir;
497
uint32_t pinVal;
498
uint16_t noisePerMS;
499
uint16_t agcCnt;
500
uint8_t aStatus;
501
uint8_t aPower;
502
uint8_t flags;
503
uint8_t reserved1;
504
uint32_t usedMask;
505
uint8_t VP[25];
506
uint8_t jamInd;
507
uint16_t reserved3;
508
uint32_t pinIrq;
509
uint32_t pullH;
510
uint32_t pullL;
511
};
512
struct PACKED ubx_mon_hw2 {
513
int8_t ofsI;
514
uint8_t magI;
515
int8_t ofsQ;
516
uint8_t magQ;
517
uint8_t cfgSource;
518
uint8_t reserved0[3];
519
uint32_t lowLevCfg;
520
uint32_t reserved1[2];
521
uint32_t postStatus;
522
uint32_t reserved2;
523
};
524
struct PACKED ubx_mon_ver {
525
char swVersion[30];
526
char hwVersion[10];
527
char extension[30*UBLOX_MAX_EXTENSIONS]; // extensions are not enabled
528
};
529
struct PACKED ubx_nav_svinfo_header {
530
uint32_t itow;
531
uint8_t numCh;
532
uint8_t globalFlags;
533
uint16_t reserved;
534
};
535
#if UBLOX_RXM_RAW_LOGGING
536
struct PACKED ubx_rxm_raw {
537
int32_t iTOW;
538
int16_t week;
539
uint8_t numSV;
540
uint8_t reserved1;
541
struct ubx_rxm_raw_sv {
542
double cpMes;
543
double prMes;
544
float doMes;
545
uint8_t sv;
546
int8_t mesQI;
547
int8_t cno;
548
uint8_t lli;
549
} svinfo[UBLOX_MAX_RXM_RAW_SATS];
550
};
551
struct PACKED ubx_rxm_rawx {
552
double rcvTow;
553
uint16_t week;
554
int8_t leapS;
555
uint8_t numMeas;
556
uint8_t recStat;
557
uint8_t reserved1[3];
558
PACKED struct ubx_rxm_rawx_sv {
559
double prMes;
560
double cpMes;
561
float doMes;
562
uint8_t gnssId;
563
uint8_t svId;
564
uint8_t reserved2;
565
uint8_t freqId;
566
uint16_t locktime;
567
uint8_t cno;
568
uint8_t prStdev;
569
uint8_t cpStdev;
570
uint8_t doStdev;
571
uint8_t trkStat;
572
uint8_t reserved3;
573
} svinfo[UBLOX_MAX_RXM_RAWX_SATS];
574
};
575
#endif
576
577
struct PACKED ubx_ack_ack {
578
uint8_t clsID;
579
uint8_t msgID;
580
};
581
struct PACKED ubx_ack_nack {
582
uint8_t clsID;
583
uint8_t msgID;
584
};
585
586
587
struct PACKED ubx_cfg_cfg {
588
uint32_t clearMask;
589
uint32_t saveMask;
590
uint32_t loadMask;
591
};
592
593
struct PACKED ubx_tim_tm2 {
594
uint8_t ch;
595
uint8_t flags;
596
uint16_t count;
597
uint16_t wnR;
598
uint16_t wnF;
599
uint32_t towMsR;
600
uint32_t towSubMsR;
601
uint32_t towMsF;
602
uint32_t towSubMsF;
603
uint32_t accEst;
604
};
605
606
// Receive buffer
607
union PACKED {
608
DEFINE_BYTE_ARRAY_METHODS
609
ubx_nav_posllh posllh;
610
ubx_nav_status status;
611
ubx_nav_dop dop;
612
ubx_nav_solution solution;
613
ubx_nav_pvt pvt;
614
ubx_nav_timegps timegps;
615
ubx_nav_velned velned;
616
ubx_cfg_msg_rate msg_rate;
617
ubx_cfg_msg_rate_6 msg_rate_6;
618
ubx_cfg_nav_settings nav_settings;
619
ubx_cfg_nav_rate nav_rate;
620
ubx_cfg_prt prt;
621
ubx_mon_hw_60 mon_hw_60;
622
ubx_mon_hw_68 mon_hw_68;
623
ubx_mon_hw2 mon_hw2;
624
ubx_mon_ver mon_ver;
625
ubx_cfg_tp5 nav_tp5;
626
#if UBLOX_GNSS_SETTINGS
627
ubx_cfg_gnss gnss;
628
#endif
629
ubx_cfg_sbas sbas;
630
ubx_cfg_valget valget;
631
ubx_nav_svinfo_header svinfo_header;
632
ubx_nav_relposned relposned;
633
#if UBLOX_RXM_RAW_LOGGING
634
ubx_rxm_raw rxm_raw;
635
ubx_rxm_rawx rxm_rawx;
636
#endif
637
ubx_ack_ack ack;
638
ubx_ack_nack nack;
639
ubx_tim_tm2 tim_tm2;
640
} _buffer;
641
642
enum class RELPOSNED {
643
gnssFixOK = 1U << 0,
644
diffSoln = 1U << 1,
645
relPosValid = 1U << 2,
646
carrSolnFloat = 1U << 3,
647
648
carrSolnFixed = 1U << 4,
649
isMoving = 1U << 5,
650
refPosMiss = 1U << 6,
651
refObsMiss = 1U << 7,
652
653
relPosHeadingValid = 1U << 8,
654
relPosNormalized = 1U << 9
655
};
656
657
enum ubs_protocol_bytes {
658
PREAMBLE1 = 0xb5,
659
PREAMBLE2 = 0x62,
660
CLASS_NAV = 0x01,
661
CLASS_ACK = 0x05,
662
CLASS_CFG = 0x06,
663
CLASS_MON = 0x0A,
664
CLASS_RXM = 0x02,
665
CLASS_TIM = 0x0d,
666
MSG_ACK_NACK = 0x00,
667
MSG_ACK_ACK = 0x01,
668
MSG_POSLLH = 0x2,
669
MSG_STATUS = 0x3,
670
MSG_DOP = 0x4,
671
MSG_SOL = 0x6,
672
MSG_PVT = 0x7,
673
MSG_TIMEGPS = 0x20,
674
MSG_RELPOSNED = 0x3c,
675
MSG_VELNED = 0x12,
676
MSG_CFG_CFG = 0x09,
677
MSG_CFG_RATE = 0x08,
678
MSG_CFG_MSG = 0x01,
679
MSG_CFG_NAV_SETTINGS = 0x24,
680
MSG_CFG_PRT = 0x00,
681
MSG_CFG_SBAS = 0x16,
682
MSG_CFG_GNSS = 0x3E,
683
MSG_CFG_TP5 = 0x31,
684
MSG_CFG_VALSET = 0x8A,
685
MSG_CFG_VALGET = 0x8B,
686
MSG_MON_HW = 0x09,
687
MSG_MON_HW2 = 0x0B,
688
MSG_MON_VER = 0x04,
689
MSG_NAV_SVINFO = 0x30,
690
MSG_RXM_RAW = 0x10,
691
MSG_RXM_RAWX = 0x15,
692
MSG_TIM_TM2 = 0x03
693
};
694
enum ubx_gnss_identifier {
695
GNSS_GPS = 0x00,
696
GNSS_SBAS = 0x01,
697
GNSS_GALILEO = 0x02,
698
GNSS_BEIDOU = 0x03,
699
GNSS_IMES = 0x04,
700
GNSS_QZSS = 0x05,
701
GNSS_GLONASS = 0x06,
702
GNSS_NAVIC = 0x07,
703
};
704
enum ubs_nav_fix_type {
705
FIX_NONE = 0,
706
FIX_DEAD_RECKONING = 1,
707
FIX_2D = 2,
708
FIX_3D = 3,
709
FIX_GPS_DEAD_RECKONING = 4,
710
FIX_TIME = 5
711
};
712
enum ubx_nav_status_bits {
713
NAV_STATUS_FIX_VALID = 1,
714
NAV_STATUS_DGPS_USED = 2
715
};
716
enum ubx_hardware_version {
717
ANTARIS = 0,
718
UBLOX_5,
719
UBLOX_6,
720
UBLOX_7,
721
UBLOX_M8,
722
UBLOX_F9 = 0x80, // comes from MON_VER hwVersion/swVersion strings
723
UBLOX_M9 = 0x81, // comes from MON_VER hwVersion/swVersion strings
724
UBLOX_M10 = 0x82,
725
UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
726
// flagging state in the driver
727
};
728
729
enum ubx_hardware_variant {
730
UBLOX_F9_ZED, // comes from MON_VER extension strings
731
UBLOX_F9_NEO, // comes from MON_VER extension strings
732
UBLOX_UNKNOWN_HARDWARE_VARIANT = 0xff
733
};
734
735
enum config_step {
736
STEP_PVT = 0,
737
STEP_NAV_RATE, // poll NAV rate
738
STEP_SOL,
739
STEP_PORT,
740
STEP_STATUS,
741
STEP_POSLLH,
742
STEP_VELNED,
743
STEP_TIMEGPS,
744
STEP_POLL_SVINFO, // poll svinfo
745
STEP_POLL_SBAS, // poll SBAS
746
STEP_POLL_NAV, // poll NAV settings
747
STEP_POLL_GNSS, // poll GNSS
748
STEP_POLL_TP5, // poll TP5
749
STEP_TMODE, // set TMODE-MODE
750
STEP_DOP,
751
STEP_MON_HW,
752
STEP_MON_HW2,
753
STEP_RAW,
754
STEP_RAWX,
755
STEP_VERSION,
756
STEP_RTK_MOVBASE, // setup moving baseline
757
STEP_TIM_TM2,
758
STEP_F9,
759
STEP_F9_VALIDATE,
760
STEP_M10,
761
STEP_L5,
762
STEP_LAST
763
};
764
765
// Packet checksum accumulators
766
uint8_t _ck_a;
767
uint8_t _ck_b;
768
769
// State machine state
770
uint8_t _step;
771
uint8_t _msg_id;
772
uint16_t _payload_length;
773
uint16_t _payload_counter;
774
775
uint8_t _class;
776
bool _cfg_saved;
777
778
uint32_t _last_vel_time;
779
uint32_t _last_pos_time;
780
uint32_t _last_cfg_sent_time;
781
uint8_t _num_cfg_save_tries;
782
uint32_t _last_config_time;
783
uint32_t _f9_config_time;
784
uint16_t _delay_time;
785
uint8_t _next_message { STEP_PVT };
786
uint8_t _ublox_port { 255 };
787
bool _have_version;
788
struct ubx_mon_ver _version;
789
char _module[UBLOX_MODULE_LEN];
790
uint32_t _unconfigured_messages {CONFIG_ALL};
791
uint8_t _hardware_generation { UBLOX_UNKNOWN_HARDWARE_GENERATION };
792
uint8_t _hardware_variant;
793
uint32_t _last_pvt_itow;
794
uint32_t _last_relposned_itow;
795
uint32_t _last_relposned_ms;
796
797
// the role set from GPS_TYPE
798
AP_GPS::GPS_Role role;
799
800
// do we have new position information?
801
bool _new_position:1;
802
// do we have new speed information?
803
bool _new_speed:1;
804
805
uint8_t _disable_counter;
806
807
// Buffer parse & GPS state update
808
bool _parse_gps();
809
810
// used to update fix between status and position packets
811
AP_GPS::GPS_Status next_fix { AP_GPS::NO_FIX };
812
813
bool _cfg_needs_save;
814
815
bool noReceivedHdop { true };
816
817
bool havePvtMsg;
818
819
// structure for list of config key/value pairs for
820
// specific configurations
821
struct PACKED config_list {
822
ConfigKey key;
823
// support up to 4 byte values, assumes little-endian
824
uint32_t value;
825
};
826
827
bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
828
bool _configure_valset(ConfigKey key, const void *value, uint8_t layers=UBX_VALSET_LAYER_ALL);
829
bool _configure_list_valset(const config_list *list, uint8_t count, uint8_t layers=UBX_VALSET_LAYER_ALL);
830
bool _configure_valget(ConfigKey key);
831
void _configure_rate(void);
832
void _configure_sbas(bool enable);
833
void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);
834
bool _send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size);
835
void send_next_rate_update(void);
836
bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);
837
void _request_next_config(void);
838
void _request_port(void);
839
void _request_version(void);
840
void _save_cfg(void);
841
void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
842
void _check_new_itow(uint32_t itow);
843
844
void unexpected_message(void);
845
void log_mon_hw(void);
846
void log_mon_hw2(void);
847
void log_tim_tm2(void);
848
void log_rxm_raw(const struct ubx_rxm_raw &raw);
849
void log_rxm_rawx(const struct ubx_rxm_rawx &raw);
850
851
#if GPS_MOVING_BASELINE
852
// see if we should use uart2 for moving baseline config
853
bool mb_use_uart2(void) const {
854
return option_set(AP_GPS::DriverOptions::UBX_MBUseUart2)?true:false;
855
}
856
#endif
857
858
// return size of a config key payload
859
uint8_t config_key_size(ConfigKey key) const;
860
861
// configure a set of config key/value pairs. The unconfig_bit corresponds to
862
// a bit in _unconfigured_messages
863
bool _configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit, uint8_t layers=UBX_VALSET_LAYER_ALL);
864
865
// find index in active_config list
866
int8_t find_active_config_index(ConfigKey key) const;
867
868
// return true if GPS is capable of F9 config
869
bool supports_F9_config(void) const;
870
871
// is the config key a GNSS key
872
bool is_gnss_key(ConfigKey key) const;
873
874
// populate config_GNSS for F9P
875
uint8_t populate_F9_gnss(void);
876
uint8_t last_configured_gnss;
877
878
uint8_t _pps_freq = 1;
879
#ifdef HAL_GPIO_PPS
880
void pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us);
881
void set_pps_desired_freq(uint8_t freq) override;
882
#endif
883
884
// status of active configuration for a role
885
struct {
886
const config_list *list;
887
uint8_t count;
888
uint32_t done_mask;
889
uint32_t unconfig_bit;
890
uint8_t layers;
891
int8_t fetch_index;
892
int8_t set_index;
893
} active_config;
894
bool use_single_valget;
895
896
#if GPS_MOVING_BASELINE
897
// config for moving baseline base
898
static const config_list config_MB_Base_uart1[];
899
static const config_list config_MB_Base_uart2[];
900
901
// config for moving baseline rover
902
static const config_list config_MB_Rover_uart1[];
903
static const config_list config_MB_Rover_uart2[];
904
905
// RTCM3 parser for when in moving baseline base mode
906
RTCM3_Parser *rtcm3_parser;
907
#endif // GPS_MOVING_BASELINE
908
909
bool supports_l5;
910
static const config_list config_M10[];
911
static const config_list config_L5_ovrd_ena[];
912
static const config_list config_L5_ovrd_dis[];
913
// scratch space for GNSS config
914
config_list* config_GNSS;
915
};
916
917
#endif
918
919