CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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