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.cpp
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 GPS driver for ArduPilot
18
// Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
19
// Substantially rewritten for new GPS driver structure by Andrew Tridgell
20
//
21
#include "AP_GPS_UBLOX.h"
22
23
#if AP_GPS_UBLOX_ENABLED
24
25
#include "AP_GPS.h"
26
#include <AP_HAL/Util.h>
27
#include <AP_Logger/AP_Logger.h>
28
#include <GCS_MAVLink/GCS.h>
29
#include "RTCM3_Parser.h"
30
#include <stdio.h>
31
32
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
33
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
34
#define UBLOX_SPEED_CHANGE 1
35
#else
36
#define UBLOX_SPEED_CHANGE 0
37
#endif
38
39
40
#define UBLOX_DEBUGGING 0
41
#define UBLOX_FAKE_3DLOCK 0
42
#ifndef CONFIGURE_PPS_PIN
43
#define CONFIGURE_PPS_PIN 0
44
#endif
45
46
// this is number of epochs per output. A higher value will reduce
47
// the uart bandwidth needed and allow for higher latency
48
#define RTK_MB_RTCM_RATE 1
49
50
// use this to enable debugging of moving baseline configs
51
#define UBLOX_MB_DEBUGGING 0
52
53
// debug VALGET/VALSET configuration
54
#define UBLOX_CFG_DEBUGGING 0
55
56
extern const AP_HAL::HAL& hal;
57
58
#if UBLOX_DEBUGGING
59
#if defined(HAL_BUILD_AP_PERIPH)
60
extern "C" {
61
void can_printf(const char *fmt, ...);
62
}
63
# define Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0)
64
#else
65
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
66
#endif
67
#else
68
# define Debug(fmt, args ...)
69
#endif
70
71
#if UBLOX_MB_DEBUGGING
72
#if defined(HAL_BUILD_AP_PERIPH)
73
extern "C" {
74
void can_printf(const char *fmt, ...);
75
}
76
# define MB_Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0)
77
#else
78
# define MB_Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
79
#endif
80
#else
81
# define MB_Debug(fmt, args ...)
82
#endif
83
84
#if UBLOX_CFG_DEBUGGING
85
#if defined(HAL_BUILD_AP_PERIPH)
86
extern "C" {
87
void can_printf(const char *fmt, ...);
88
}
89
# define CFG_Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0)
90
#else
91
# define CFG_Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
92
#endif
93
#else
94
# define CFG_Debug(fmt, args ...)
95
#endif
96
97
AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps,
98
AP_GPS::Params &_params,
99
AP_GPS::GPS_State &_state,
100
AP_HAL::UARTDriver *_port,
101
AP_GPS::GPS_Role _role) :
102
AP_GPS_Backend(_gps, _params, _state, _port),
103
role(_role)
104
{
105
// stop any config strings that are pending
106
gps.send_blob_start(state.instance, nullptr, 0);
107
108
// start the process of updating the GPS rates
109
_request_next_config();
110
111
#if CONFIGURE_PPS_PIN
112
_unconfigured_messages |= CONFIG_TP5;
113
#endif
114
115
#if GPS_MOVING_BASELINE
116
if (role == AP_GPS::GPS_ROLE_MB_BASE && !mb_use_uart2()) {
117
rtcm3_parser = NEW_NOTHROW RTCM3_Parser;
118
if (rtcm3_parser == nullptr) {
119
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "u-blox %d: failed RTCMv3 parser allocation", state.instance + 1);
120
}
121
_unconfigured_messages |= CONFIG_RTK_MOVBASE;
122
}
123
if (role == AP_GPS::GPS_ROLE_MB_ROVER) {
124
_unconfigured_messages |= CONFIG_RTK_MOVBASE;
125
state.gps_yaw_configured = true;
126
}
127
#endif
128
}
129
130
AP_GPS_UBLOX::~AP_GPS_UBLOX()
131
{
132
#if GPS_MOVING_BASELINE
133
delete rtcm3_parser;
134
#endif
135
}
136
137
#if GPS_MOVING_BASELINE
138
/*
139
config for F9 GPS in moving baseline base role
140
See ZED-F9P integration manual section 3.1.5.6.1
141
*/
142
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_MB_Base_uart1[] {
143
{ ConfigKey::CFG_UART1OUTPROT_RTCM3X, 1},
144
{ ConfigKey::CFG_UART2OUTPROT_RTCM3X, 0},
145
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART1, 0},
146
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART2, 0},
147
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART1, RTK_MB_RTCM_RATE},
148
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART1, RTK_MB_RTCM_RATE},
149
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART1, RTK_MB_RTCM_RATE},
150
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART1, RTK_MB_RTCM_RATE},
151
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART1, RTK_MB_RTCM_RATE},
152
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART1, RTK_MB_RTCM_RATE},
153
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART1, RTK_MB_RTCM_RATE},
154
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART2, 0},
155
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART2, 0},
156
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART2, 0},
157
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART2, 0},
158
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART2, 0},
159
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART2, 0},
160
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART2, 0},
161
};
162
163
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_MB_Base_uart2[] {
164
{ ConfigKey::CFG_UART2_ENABLED, 1},
165
{ ConfigKey::CFG_UART2_BAUDRATE, 460800},
166
{ ConfigKey::CFG_UART2OUTPROT_RTCM3X, 1},
167
{ ConfigKey::CFG_UART1OUTPROT_RTCM3X, 0},
168
{ ConfigKey::CFG_UART1INPROT_RTCM3X, 1},
169
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART2, 0},
170
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART1, 0},
171
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART2, RTK_MB_RTCM_RATE},
172
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART2, RTK_MB_RTCM_RATE},
173
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART2, RTK_MB_RTCM_RATE},
174
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART2, RTK_MB_RTCM_RATE},
175
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART2, RTK_MB_RTCM_RATE},
176
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART2, RTK_MB_RTCM_RATE},
177
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART2, RTK_MB_RTCM_RATE},
178
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART1, 0},
179
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART1, 0},
180
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART1, 0},
181
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART1, 0},
182
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART1, 0},
183
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART1, 0},
184
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART1, 0},
185
};
186
187
188
/*
189
config for F9 GPS in moving baseline rover role
190
See ZED-F9P integration manual section 3.1.5.6.1.
191
Note that we list the RTCM msg types as 0 to prevent getting RTCM
192
data from a GPS previously configured as a base
193
*/
194
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_MB_Rover_uart1[] {
195
{ ConfigKey::CFG_UART2OUTPROT_RTCM3X, 0},
196
{ ConfigKey::CFG_UART1INPROT_RTCM3X, 1},
197
{ ConfigKey::CFG_UART2INPROT_RTCM3X, 0},
198
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART1, 1},
199
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART2, 0},
200
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART1, 0},
201
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART1, 0},
202
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART1, 0},
203
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART1, 0},
204
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART1, 0},
205
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART1, 0},
206
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART1, 0},
207
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART2, 0},
208
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART2, 0},
209
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART2, 0},
210
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART2, 0},
211
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART2, 0},
212
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART2, 0},
213
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART2, 0},
214
};
215
216
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_MB_Rover_uart2[] {
217
{ ConfigKey::CFG_UART2_ENABLED, 1},
218
{ ConfigKey::CFG_UART2_BAUDRATE, 460800},
219
{ ConfigKey::CFG_UART2OUTPROT_RTCM3X, 0},
220
{ ConfigKey::CFG_UART2INPROT_RTCM3X, 1},
221
{ ConfigKey::CFG_UART1INPROT_RTCM3X, 0},
222
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART1, 1},
223
{ ConfigKey::MSGOUT_UBX_NAV_RELPOSNED_UART2, 0},
224
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART2, 0},
225
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART2, 0},
226
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART2, 0},
227
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART2, 0},
228
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART2, 0},
229
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART2, 0},
230
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART2, 0},
231
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_0_UART1, 0},
232
{ ConfigKey::MSGOUT_RTCM_3X_TYPE4072_1_UART1, 0},
233
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1077_UART1, 0},
234
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1087_UART1, 0},
235
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1097_UART1, 0},
236
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1127_UART1, 0},
237
{ ConfigKey::MSGOUT_RTCM_3X_TYPE1230_UART1, 0},
238
};
239
#endif // GPS_MOVING_BASELINE
240
241
/*
242
config changes for M10
243
we need to use B1C not B1 signal for Beidou on M10 to allow solid 5Hz,
244
and also disable Glonass and enable QZSS
245
*/
246
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_M10[] {
247
{ ConfigKey::CFG_SIGNAL_BDS_ENA, 1},
248
{ ConfigKey::CFG_SIGNAL_BDS_B1_ENA, 0},
249
{ ConfigKey::CFG_SIGNAL_BDS_B1C_ENA, 1},
250
{ ConfigKey::CFG_SIGNAL_GLO_ENA, 0},
251
{ ConfigKey::CFG_SIGNAL_QZSS_ENA, 1},
252
{ ConfigKey::CFG_SIGNAL_QZSS_L1CA_ENA, 1},
253
{ ConfigKey::CFG_SIGNAL_QZSS_L1S_ENA, 1},
254
{ ConfigKey::CFG_NAVSPG_DYNMODEL, 8}, // Air < 4g
255
};
256
257
258
/*
259
config changes for L5 modules
260
*/
261
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_L5_ovrd_ena[] {
262
{ConfigKey::CFG_SIGNAL_L5_HEALTH_OVRD, 1},
263
{ConfigKey::CFG_SIGNAL_GPS_L5_ENA, 1},
264
};
265
266
const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_L5_ovrd_dis[] {
267
{ConfigKey::CFG_SIGNAL_L5_HEALTH_OVRD, 0},
268
};
269
270
void
271
AP_GPS_UBLOX::_request_next_config(void)
272
{
273
// don't request config if we shouldn't configure the GPS
274
if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
275
return;
276
}
277
278
// Ensure there is enough space for the largest possible outgoing message
279
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_nav_rate)+2)) {
280
// not enough space - do it next time
281
return;
282
}
283
284
if (_unconfigured_messages == CONFIG_RATE_SOL && havePvtMsg) {
285
/*
286
we don't need SOL if we have PVT and TIMEGPS. This is needed
287
as F9P doesn't support the SOL message
288
*/
289
_unconfigured_messages &= ~CONFIG_RATE_SOL;
290
}
291
292
Debug("Unconfigured messages: 0x%x Current message: %u\n", (unsigned)_unconfigured_messages, (unsigned)_next_message);
293
294
// check AP_GPS_UBLOX.h for the enum that controls the order.
295
// This switch statement isn't maintained against the enum in order to reduce code churn
296
switch (_next_message++) {
297
case STEP_PVT:
298
if(!_request_message_rate(CLASS_NAV, MSG_PVT)) {
299
_next_message--;
300
}
301
break;
302
case STEP_TIMEGPS:
303
if(!_request_message_rate(CLASS_NAV, MSG_TIMEGPS)) {
304
_next_message--;
305
}
306
break;
307
case STEP_PORT:
308
_request_port();
309
break;
310
case STEP_POLL_SVINFO:
311
// not required once we know what generation we are on
312
if(_hardware_generation == UBLOX_UNKNOWN_HARDWARE_GENERATION) {
313
if (!_send_message(CLASS_NAV, MSG_NAV_SVINFO, 0, 0)) {
314
_next_message--;
315
}
316
}
317
break;
318
case STEP_POLL_SBAS:
319
if (gps._sbas_mode != AP_GPS::SBAS_Mode::DoNotChange) {
320
_send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0);
321
} else {
322
_unconfigured_messages &= ~CONFIG_SBAS;
323
}
324
break;
325
case STEP_POLL_NAV:
326
if (!_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0)) {
327
_next_message--;
328
}
329
break;
330
case STEP_POLL_GNSS:
331
if (supports_F9_config()) {
332
if (last_configured_gnss != params.gnss_mode) {
333
_unconfigured_messages |= CONFIG_F9;
334
}
335
break;
336
}
337
if (!_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0)) {
338
_next_message--;
339
}
340
break;
341
case STEP_POLL_TP5:
342
#if CONFIGURE_PPS_PIN
343
if (!_send_message(CLASS_CFG, MSG_CFG_TP5, nullptr, 0)) {
344
_next_message--;
345
}
346
#endif
347
break;
348
case STEP_NAV_RATE:
349
if (!_send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0)) {
350
_next_message--;
351
}
352
break;
353
case STEP_POSLLH:
354
if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) {
355
_next_message--;
356
}
357
break;
358
case STEP_STATUS:
359
if(!_request_message_rate(CLASS_NAV, MSG_STATUS)) {
360
_next_message--;
361
}
362
break;
363
case STEP_SOL:
364
if(!_request_message_rate(CLASS_NAV, MSG_SOL)) {
365
_next_message--;
366
}
367
break;
368
case STEP_VELNED:
369
if(!_request_message_rate(CLASS_NAV, MSG_VELNED)) {
370
_next_message--;
371
}
372
break;
373
case STEP_DOP:
374
if(! _request_message_rate(CLASS_NAV, MSG_DOP)) {
375
_next_message--;
376
}
377
break;
378
case STEP_MON_HW:
379
if(!_request_message_rate(CLASS_MON, MSG_MON_HW)) {
380
_next_message--;
381
}
382
break;
383
case STEP_MON_HW2:
384
if(!_request_message_rate(CLASS_MON, MSG_MON_HW2)) {
385
_next_message--;
386
}
387
break;
388
case STEP_RAW:
389
#if UBLOX_RXM_RAW_LOGGING
390
if(gps._raw_data == 0) {
391
_unconfigured_messages &= ~CONFIG_RATE_RAW;
392
} else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAW)) {
393
_next_message--;
394
}
395
#else
396
_unconfigured_messages & = ~CONFIG_RATE_RAW;
397
#endif
398
break;
399
case STEP_RAWX:
400
#if UBLOX_RXM_RAW_LOGGING
401
if(gps._raw_data == 0) {
402
_unconfigured_messages &= ~CONFIG_RATE_RAW;
403
} else if(!_request_message_rate(CLASS_RXM, MSG_RXM_RAWX)) {
404
_next_message--;
405
}
406
#else
407
_unconfigured_messages & = ~CONFIG_RATE_RAW;
408
#endif
409
break;
410
case STEP_VERSION:
411
if(!_have_version && !hal.util->get_soft_armed()) {
412
_request_version();
413
} else {
414
_unconfigured_messages &= ~CONFIG_VERSION;
415
}
416
break;
417
case STEP_TMODE:
418
if (supports_F9_config()) {
419
if (!_configure_valget(ConfigKey::TMODE_MODE)) {
420
_next_message--;
421
}
422
}
423
break;
424
case STEP_RTK_MOVBASE:
425
#if GPS_MOVING_BASELINE
426
if (supports_F9_config()) {
427
static_assert(sizeof(active_config.done_mask)*8 >= ARRAY_SIZE(config_MB_Base_uart1), "done_mask too small, base1");
428
static_assert(sizeof(active_config.done_mask)*8 >= ARRAY_SIZE(config_MB_Base_uart2), "done_mask too small, base2");
429
static_assert(sizeof(active_config.done_mask)*8 >= ARRAY_SIZE(config_MB_Rover_uart1), "done_mask too small, rover1");
430
static_assert(sizeof(active_config.done_mask)*8 >= ARRAY_SIZE(config_MB_Rover_uart2), "done_mask too small, rover2");
431
if (role == AP_GPS::GPS_ROLE_MB_BASE) {
432
const config_list *list = mb_use_uart2()?config_MB_Base_uart2:config_MB_Base_uart1;
433
uint8_t list_length = mb_use_uart2()?ARRAY_SIZE(config_MB_Base_uart2):ARRAY_SIZE(config_MB_Base_uart1);
434
if (!_configure_config_set(list, list_length, CONFIG_RTK_MOVBASE)) {
435
_next_message--;
436
}
437
}
438
if (role == AP_GPS::GPS_ROLE_MB_ROVER) {
439
const config_list *list = mb_use_uart2()?config_MB_Rover_uart2:config_MB_Rover_uart1;
440
uint8_t list_length = mb_use_uart2()?ARRAY_SIZE(config_MB_Rover_uart2):ARRAY_SIZE(config_MB_Rover_uart1);
441
if (!_configure_config_set(list, list_length, CONFIG_RTK_MOVBASE)) {
442
_next_message--;
443
}
444
}
445
}
446
#endif
447
break;
448
case STEP_TIM_TM2:
449
#if UBLOX_TIM_TM2_LOGGING
450
if(!_request_message_rate(CLASS_TIM, MSG_TIM_TM2)) {
451
_next_message--;
452
}
453
#else
454
_unconfigured_messages &= ~CONFIG_TIM_TM2;
455
#endif
456
break;
457
458
case STEP_F9: {
459
if (_hardware_generation == UBLOX_F9) {
460
uint8_t cfg_count = populate_F9_gnss();
461
// special handling of F9 config
462
if (cfg_count > 0) {
463
CFG_Debug("Sending F9 settings, GNSS=%u", params.gnss_mode);
464
465
if (!_configure_list_valset(config_GNSS, cfg_count, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
466
_next_message--;
467
break;
468
}
469
_f9_config_time = AP_HAL::millis();
470
}
471
}
472
break;
473
}
474
475
case STEP_F9_VALIDATE: {
476
if (_hardware_generation == UBLOX_F9) {
477
// GNSS takes 0.5s to reset
478
if (AP_HAL::millis() - _f9_config_time < 500) {
479
_next_message--;
480
break;
481
}
482
_f9_config_time = 0;
483
uint8_t cfg_count = populate_F9_gnss();
484
// special handling of F9 config
485
if (cfg_count > 0) {
486
CFG_Debug("Validating F9 settings, GNSS=%u", params.gnss_mode);
487
// now validate all of the settings, this is a no-op if the first call succeeded
488
if (!_configure_config_set(config_GNSS, cfg_count, CONFIG_F9, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
489
_next_message--;
490
}
491
}
492
}
493
break;
494
}
495
case STEP_M10: {
496
if (_hardware_generation == UBLOX_M10) {
497
// special handling of M10 config
498
const config_list *list = config_M10;
499
const uint8_t list_length = ARRAY_SIZE(config_M10);
500
Debug("Sending M10 settings");
501
if (!_configure_config_set(list, list_length, CONFIG_M10, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
502
_next_message--;
503
}
504
}
505
break;
506
}
507
508
case STEP_L5: {
509
if (supports_l5 && option_set(AP_GPS::DriverOptions::GPSL5HealthOverride)) {
510
const config_list *list = config_L5_ovrd_ena;
511
const uint8_t list_length = ARRAY_SIZE(config_L5_ovrd_ena);
512
if (!_configure_config_set(list, list_length, CONFIG_L5, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
513
_next_message--;
514
}
515
} else if (supports_l5 && !option_set(AP_GPS::DriverOptions::GPSL5HealthOverride)) {
516
const config_list *list = config_L5_ovrd_dis;
517
const uint8_t list_length = ARRAY_SIZE(config_L5_ovrd_dis);
518
if (!_configure_config_set(list, list_length, CONFIG_L5, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
519
_next_message--;
520
}
521
}
522
break;
523
}
524
525
default:
526
// this case should never be reached, do a full reset if it is hit
527
_next_message = STEP_PVT;
528
break;
529
}
530
}
531
532
void
533
AP_GPS_UBLOX::_verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) {
534
uint8_t desired_rate;
535
uint32_t config_msg_id;
536
switch(msg_class) {
537
case CLASS_NAV:
538
switch(msg_id) {
539
case MSG_POSLLH:
540
desired_rate = havePvtMsg ? 0 : RATE_POSLLH;
541
config_msg_id = CONFIG_RATE_POSLLH;
542
break;
543
case MSG_STATUS:
544
desired_rate = havePvtMsg ? 0 : RATE_STATUS;
545
config_msg_id = CONFIG_RATE_STATUS;
546
break;
547
case MSG_SOL:
548
desired_rate = havePvtMsg ? 0 : RATE_SOL;
549
config_msg_id = CONFIG_RATE_SOL;
550
break;
551
case MSG_PVT:
552
desired_rate = RATE_PVT;
553
config_msg_id = CONFIG_RATE_PVT;
554
break;
555
case MSG_TIMEGPS:
556
desired_rate = RATE_TIMEGPS;
557
config_msg_id = CONFIG_RATE_TIMEGPS;
558
break;
559
case MSG_VELNED:
560
desired_rate = havePvtMsg ? 0 : RATE_VELNED;
561
config_msg_id = CONFIG_RATE_VELNED;
562
break;
563
case MSG_DOP:
564
desired_rate = RATE_DOP;
565
config_msg_id = CONFIG_RATE_DOP;
566
break;
567
default:
568
return;
569
}
570
break;
571
case CLASS_MON:
572
switch(msg_id) {
573
case MSG_MON_HW:
574
desired_rate = RATE_HW;
575
config_msg_id = CONFIG_RATE_MON_HW;
576
break;
577
case MSG_MON_HW2:
578
desired_rate = RATE_HW2;
579
config_msg_id = CONFIG_RATE_MON_HW2;
580
break;
581
default:
582
return;
583
}
584
break;
585
#if UBLOX_RXM_RAW_LOGGING
586
case CLASS_RXM:
587
switch(msg_id) {
588
case MSG_RXM_RAW:
589
desired_rate = gps._raw_data;
590
config_msg_id = CONFIG_RATE_RAW;
591
break;
592
case MSG_RXM_RAWX:
593
desired_rate = gps._raw_data;
594
config_msg_id = CONFIG_RATE_RAW;
595
break;
596
default:
597
return;
598
}
599
break;
600
#endif // UBLOX_RXM_RAW_LOGGING
601
#if UBLOX_TIM_TM2_LOGGING
602
case CLASS_TIM:
603
if (msg_id == MSG_TIM_TM2) {
604
desired_rate = RATE_TIM_TM2;
605
config_msg_id = CONFIG_TIM_TM2;
606
break;
607
}
608
return;
609
#endif // UBLOX_TIM_TM2_LOGGING
610
default:
611
return;
612
}
613
614
if (rate == desired_rate) {
615
// coming in at correct rate; mark as configured
616
_unconfigured_messages &= ~config_msg_id;
617
return;
618
}
619
620
// coming in at wrong rate; try to configure it
621
_configure_message_rate(msg_class, msg_id, desired_rate);
622
_unconfigured_messages |= config_msg_id;
623
_cfg_needs_save = true;
624
}
625
626
// Requests the ublox driver to identify what port we are using to communicate
627
void
628
AP_GPS_UBLOX::_request_port(void)
629
{
630
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+2)) {
631
// not enough space - do it next time
632
return;
633
}
634
_send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0);
635
}
636
637
// Ensure there is enough space for the largest possible outgoing message
638
// Process bytes available from the stream
639
//
640
// The stream is assumed to contain only messages we recognise. If it
641
// contains other messages, and those messages contain the preamble
642
// bytes, it is possible for this code to fail to synchronise to the
643
// stream immediately. Without buffering the entire message and
644
// re-processing it from the top, this is unavoidable. The parser
645
// attempts to avoid this when possible.
646
//
647
bool
648
AP_GPS_UBLOX::read(void)
649
{
650
bool parsed = false;
651
uint32_t millis_now = AP_HAL::millis();
652
653
// walk through the gps configuration at 1 message per second
654
if (millis_now - _last_config_time >= _delay_time) {
655
_request_next_config();
656
_last_config_time = millis_now;
657
if (_unconfigured_messages) { // send the updates faster until fully configured
658
if (!havePvtMsg && (_unconfigured_messages & CONFIG_REQUIRED_INITIAL)) {
659
_delay_time = 300;
660
} else {
661
_delay_time = 750;
662
}
663
} else {
664
_delay_time = 2000;
665
}
666
}
667
668
if(!_unconfigured_messages && gps._save_config && !_cfg_saved &&
669
_num_cfg_save_tries < 5 && (millis_now - _last_cfg_sent_time) > 5000 &&
670
!hal.util->get_soft_armed()) {
671
//save the configuration sent until now
672
if (gps._save_config == 1 ||
673
(gps._save_config == 2 && _cfg_needs_save)) {
674
_save_cfg();
675
}
676
}
677
678
const uint16_t numc = MIN(port->available(), 8192U);
679
for (uint16_t i = 0; i < numc; i++) { // Process bytes received
680
681
// read the next byte
682
uint8_t data;
683
if (!port->read(data)) {
684
break;
685
}
686
#if AP_GPS_DEBUG_LOGGING_ENABLED
687
log_data(&data, 1);
688
#endif
689
690
#if GPS_MOVING_BASELINE
691
if (rtcm3_parser) {
692
if (rtcm3_parser->read(data)) {
693
// we've found a RTCMv3 packet. We stop parsing at
694
// this point and reset u-blox parse state. We need to
695
// stop parsing to give the higher level driver a
696
// chance to send the RTCMv3 packet to another (rover)
697
// GPS
698
_step = 0;
699
break;
700
}
701
}
702
#endif
703
704
reset:
705
switch(_step) {
706
707
// Message preamble detection
708
//
709
// If we fail to match any of the expected bytes, we reset
710
// the state machine and re-consider the failed byte as
711
// the first byte of the preamble. This improves our
712
// chances of recovering from a mismatch and makes it less
713
// likely that we will be fooled by the preamble appearing
714
// as data in some other message.
715
//
716
case 1:
717
if (PREAMBLE2 == data) {
718
_step++;
719
break;
720
}
721
_step = 0;
722
Debug("reset %u", __LINE__);
723
FALLTHROUGH;
724
case 0:
725
if(PREAMBLE1 == data)
726
_step++;
727
break;
728
729
// Message header processing
730
//
731
// We sniff the class and message ID to decide whether we
732
// are going to gather the message bytes or just discard
733
// them.
734
//
735
// We always collect the length so that we can avoid being
736
// fooled by preamble bytes in messages.
737
//
738
case 2:
739
_step++;
740
_class = data;
741
_ck_b = _ck_a = data; // reset the checksum accumulators
742
break;
743
case 3:
744
_step++;
745
_ck_b += (_ck_a += data); // checksum byte
746
_msg_id = data;
747
break;
748
case 4:
749
_step++;
750
_ck_b += (_ck_a += data); // checksum byte
751
_payload_length = data; // payload length low byte
752
break;
753
case 5:
754
_step++;
755
_ck_b += (_ck_a += data); // checksum byte
756
757
_payload_length += (uint16_t)(data<<8);
758
if (_payload_length > sizeof(_buffer)) {
759
Debug("large payload %u", (unsigned)_payload_length);
760
// assume any payload bigger then what we know about is noise
761
_payload_length = 0;
762
_step = 0;
763
goto reset;
764
}
765
_payload_counter = 0; // prepare to receive payload
766
if (_payload_length == 0) {
767
// bypass payload and go straight to checksum
768
_step++;
769
}
770
break;
771
772
// Receive message data
773
//
774
case 6:
775
_ck_b += (_ck_a += data); // checksum byte
776
if (_payload_counter < sizeof(_buffer)) {
777
_buffer[_payload_counter] = data;
778
}
779
if (++_payload_counter == _payload_length)
780
_step++;
781
break;
782
783
// Checksum and message processing
784
//
785
case 7:
786
_step++;
787
if (_ck_a != data) {
788
Debug("bad cka %x should be %x", data, _ck_a);
789
_step = 0;
790
goto reset;
791
}
792
break;
793
case 8:
794
_step = 0;
795
if (_ck_b != data) {
796
Debug("bad ckb %x should be %x", data, _ck_b);
797
break; // bad checksum
798
}
799
800
#if GPS_MOVING_BASELINE
801
if (rtcm3_parser) {
802
// this is a uBlox packet, discard any partial RTCMv3 state
803
rtcm3_parser->reset();
804
}
805
#endif
806
if (_parse_gps()) {
807
parsed = true;
808
}
809
break;
810
}
811
}
812
return parsed;
813
}
814
815
// Private Methods /////////////////////////////////////////////////////////////
816
void AP_GPS_UBLOX::log_mon_hw(void)
817
{
818
#if HAL_LOGGING_ENABLED
819
if (!should_log()) {
820
return;
821
}
822
struct log_Ubx1 pkt = {
823
LOG_PACKET_HEADER_INIT(LOG_GPS_UBX1_MSG),
824
time_us : AP_HAL::micros64(),
825
instance : state.instance,
826
noisePerMS : _buffer.mon_hw_60.noisePerMS,
827
jamInd : _buffer.mon_hw_60.jamInd,
828
aPower : _buffer.mon_hw_60.aPower,
829
agcCnt : _buffer.mon_hw_60.agcCnt,
830
config : _unconfigured_messages,
831
};
832
if (_payload_length == 68) {
833
pkt.noisePerMS = _buffer.mon_hw_68.noisePerMS;
834
pkt.jamInd = _buffer.mon_hw_68.jamInd;
835
pkt.aPower = _buffer.mon_hw_68.aPower;
836
pkt.agcCnt = _buffer.mon_hw_68.agcCnt;
837
}
838
AP::logger().WriteBlock(&pkt, sizeof(pkt));
839
#endif
840
}
841
842
void AP_GPS_UBLOX::log_mon_hw2(void)
843
{
844
#if HAL_LOGGING_ENABLED
845
if (!should_log()) {
846
return;
847
}
848
849
struct log_Ubx2 pkt = {
850
LOG_PACKET_HEADER_INIT(LOG_GPS_UBX2_MSG),
851
time_us : AP_HAL::micros64(),
852
instance : state.instance,
853
ofsI : _buffer.mon_hw2.ofsI,
854
magI : _buffer.mon_hw2.magI,
855
ofsQ : _buffer.mon_hw2.ofsQ,
856
magQ : _buffer.mon_hw2.magQ,
857
};
858
AP::logger().WriteBlock(&pkt, sizeof(pkt));
859
#endif
860
}
861
862
#if UBLOX_TIM_TM2_LOGGING
863
void AP_GPS_UBLOX::log_tim_tm2(void)
864
{
865
#if HAL_LOGGING_ENABLED
866
if (!should_log()) {
867
return;
868
}
869
870
// @LoggerMessage: UBXT
871
// @Description: uBlox specific UBX-TIM-TM2 logging, see uBlox interface description
872
// @Field: TimeUS: Time since system startup
873
// @Field: I: GPS instance number
874
// @Field: ch: Channel (i.e. EXTINT) upon which the pulse was measured
875
// @Field: flags: Bitmask
876
// @Field: count: Rising edge counter
877
// @Field: wnR: Week number of last rising edge
878
// @Field: MsR: Tow of rising edge
879
// @Field: SubMsR: Millisecond fraction of tow of rising edge in nanoseconds
880
// @Field: wnF: Week number of last falling edge
881
// @Field: MsF: Tow of falling edge
882
// @Field: SubMsF: Millisecond fraction of tow of falling edge in nanoseconds
883
// @Field: accEst: Accuracy estimate
884
885
AP::logger().WriteStreaming("UBXT",
886
"TimeUS,I,ch,flags,count,wnR,MsR,SubMsR,wnF,MsF,SubMsF,accEst",
887
"s#----ss-sss",
888
"F-----CI-CII",
889
"QBBBHHIIHIII",
890
AP_HAL::micros64(),
891
state.instance,
892
_buffer.tim_tm2.ch,
893
_buffer.tim_tm2.flags,
894
_buffer.tim_tm2.count,
895
_buffer.tim_tm2.wnR,
896
_buffer.tim_tm2.towMsR,
897
_buffer.tim_tm2.towSubMsR,
898
_buffer.tim_tm2.wnF,
899
_buffer.tim_tm2.towMsF,
900
_buffer.tim_tm2.towSubMsF,
901
_buffer.tim_tm2.accEst);
902
#endif
903
}
904
#endif // UBLOX_TIM_TM2_LOGGING
905
906
#if UBLOX_RXM_RAW_LOGGING
907
void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
908
{
909
#if HAL_LOGGING_ENABLED
910
if (!should_log()) {
911
return;
912
}
913
914
uint64_t now = AP_HAL::micros64();
915
for (uint8_t i=0; i<raw.numSV; i++) {
916
struct log_GPS_RAW pkt = {
917
LOG_PACKET_HEADER_INIT(LOG_GPS_RAW_MSG),
918
time_us : now,
919
iTOW : raw.iTOW,
920
week : raw.week,
921
numSV : raw.numSV,
922
sv : raw.svinfo[i].sv,
923
cpMes : raw.svinfo[i].cpMes,
924
prMes : raw.svinfo[i].prMes,
925
doMes : raw.svinfo[i].doMes,
926
mesQI : raw.svinfo[i].mesQI,
927
cno : raw.svinfo[i].cno,
928
lli : raw.svinfo[i].lli
929
};
930
AP::logger().WriteBlock(&pkt, sizeof(pkt));
931
}
932
#endif
933
}
934
935
void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
936
{
937
#if HAL_LOGGING_ENABLED
938
if (!should_log()) {
939
return;
940
}
941
942
uint64_t now = AP_HAL::micros64();
943
944
struct log_GPS_RAWH header = {
945
LOG_PACKET_HEADER_INIT(LOG_GPS_RAWH_MSG),
946
time_us : now,
947
rcvTow : raw.rcvTow,
948
week : raw.week,
949
leapS : raw.leapS,
950
numMeas : raw.numMeas,
951
recStat : raw.recStat
952
};
953
AP::logger().WriteBlock(&header, sizeof(header));
954
955
for (uint8_t i=0; i<raw.numMeas; i++) {
956
struct log_GPS_RAWS pkt = {
957
LOG_PACKET_HEADER_INIT(LOG_GPS_RAWS_MSG),
958
time_us : now,
959
prMes : raw.svinfo[i].prMes,
960
cpMes : raw.svinfo[i].cpMes,
961
doMes : raw.svinfo[i].doMes,
962
gnssId : raw.svinfo[i].gnssId,
963
svId : raw.svinfo[i].svId,
964
freqId : raw.svinfo[i].freqId,
965
locktime : raw.svinfo[i].locktime,
966
cno : raw.svinfo[i].cno,
967
prStdev : raw.svinfo[i].prStdev,
968
cpStdev : raw.svinfo[i].cpStdev,
969
doStdev : raw.svinfo[i].doStdev,
970
trkStat : raw.svinfo[i].trkStat
971
};
972
AP::logger().WriteBlock(&pkt, sizeof(pkt));
973
}
974
#endif
975
}
976
#endif // UBLOX_RXM_RAW_LOGGING
977
978
void AP_GPS_UBLOX::unexpected_message(void)
979
{
980
Debug("Unexpected message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
981
if (++_disable_counter == 0) {
982
// disable future sends of this message id, but
983
// only do this every 256 messages, as some
984
// message types can't be disabled and we don't
985
// want to get into an ack war
986
Debug("Disabling message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
987
_configure_message_rate(_class, _msg_id, 0);
988
}
989
}
990
991
// return size of a config key, or 0 if unknown
992
uint8_t AP_GPS_UBLOX::config_key_size(ConfigKey key) const
993
{
994
// step over the value
995
const uint8_t key_size = (uint32_t(key) >> 28) & 0x07; // mask off the storage size
996
switch (key_size) {
997
case 0x1: // bit
998
case 0x2: // byte
999
return 1;
1000
case 0x3: // 2 bytes
1001
return 2;
1002
case 0x4: // 4 bytes
1003
return 4;
1004
case 0x5: // 8 bytes
1005
return 8;
1006
default:
1007
break;
1008
}
1009
// invalid
1010
return 0;
1011
}
1012
1013
/*
1014
find index of a config key in the active_config list, or -1
1015
*/
1016
int8_t AP_GPS_UBLOX::find_active_config_index(ConfigKey key) const
1017
{
1018
if (active_config.list == nullptr) {
1019
return -1;
1020
}
1021
for (uint8_t i=0; i<active_config.count; i++) {
1022
if (key == active_config.list[i].key) {
1023
return (int8_t)i;
1024
}
1025
}
1026
1027
return -1;
1028
}
1029
1030
bool
1031
AP_GPS_UBLOX::_parse_gps(void)
1032
{
1033
if (_class == CLASS_ACK) {
1034
Debug("ACK %u", (unsigned)_msg_id);
1035
1036
if(_msg_id == MSG_ACK_ACK) {
1037
switch(_buffer.ack.clsID) {
1038
case CLASS_CFG:
1039
switch(_buffer.ack.msgID) {
1040
case MSG_CFG_CFG:
1041
_cfg_saved = true;
1042
_cfg_needs_save = false;
1043
break;
1044
case MSG_CFG_GNSS:
1045
_unconfigured_messages &= ~CONFIG_GNSS;
1046
break;
1047
case MSG_CFG_MSG:
1048
// There is no way to know what MSG config was ack'ed, assume it was the last
1049
// one requested. To verify it rerequest the last config we sent. If we miss
1050
// the actual ack we will catch it next time through the poll loop, but that
1051
// will be a good chunk of time later.
1052
break;
1053
case MSG_CFG_NAV_SETTINGS:
1054
_unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
1055
break;
1056
case MSG_CFG_RATE:
1057
// The GPS will ACK a update rate that is invalid. in order to detect this
1058
// only accept the rate as configured by reading the settings back and
1059
// validating that they all match the target values
1060
break;
1061
case MSG_CFG_SBAS:
1062
_unconfigured_messages &= ~CONFIG_SBAS;
1063
break;
1064
case MSG_CFG_TP5:
1065
_unconfigured_messages &= ~CONFIG_TP5;
1066
break;
1067
}
1068
1069
break;
1070
case CLASS_MON:
1071
switch(_buffer.ack.msgID) {
1072
case MSG_MON_HW:
1073
_unconfigured_messages &= ~CONFIG_RATE_MON_HW;
1074
break;
1075
case MSG_MON_HW2:
1076
_unconfigured_messages &= ~CONFIG_RATE_MON_HW2;
1077
break;
1078
}
1079
}
1080
}
1081
if(_msg_id == MSG_ACK_NACK) {
1082
switch(_buffer.nack.clsID) {
1083
case CLASS_CFG:
1084
switch(_buffer.nack.msgID) {
1085
case MSG_CFG_VALGET:
1086
CFG_Debug("NACK VALGET 0x%x", (unsigned)_buffer.nack.msgID);
1087
if (active_config.list != nullptr) {
1088
/*
1089
likely this device does not support fetching multiple keys at once, go one at a time
1090
*/
1091
if (active_config.fetch_index == -1) {
1092
CFG_Debug("NACK starting %u", unsigned(active_config.count));
1093
active_config.fetch_index = 0;
1094
} else {
1095
// the device does not support the config key we asked for,
1096
// consider the bit as done
1097
active_config.done_mask |= (1U<<active_config.fetch_index);
1098
CFG_Debug("NACK %d 0x%x done=0x%x",
1099
int(active_config.fetch_index),
1100
unsigned(active_config.list[active_config.fetch_index].key),
1101
unsigned(active_config.done_mask));
1102
if (active_config.done_mask == (1U<<active_config.count)-1) {
1103
// all done!
1104
_unconfigured_messages &= ~active_config.unconfig_bit;
1105
}
1106
active_config.fetch_index++;
1107
}
1108
if (active_config.fetch_index < active_config.count) {
1109
_configure_valget(active_config.list[active_config.fetch_index].key);
1110
}
1111
}
1112
break;
1113
case MSG_CFG_VALSET:
1114
CFG_Debug("NACK VALSET 0x%x 0x%x", (unsigned)_buffer.nack.msgID,
1115
unsigned(active_config.list[active_config.set_index].key));
1116
if (is_gnss_key(active_config.list[active_config.set_index].key)) {
1117
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "GPS %u: unable to configure band 0x%02x",
1118
unsigned(state.instance + 1), unsigned(active_config.list[active_config.set_index].key));
1119
1120
}
1121
break;
1122
}
1123
}
1124
}
1125
return false;
1126
}
1127
1128
if (_class == CLASS_CFG) {
1129
switch(_msg_id) {
1130
case MSG_CFG_NAV_SETTINGS:
1131
Debug("Got settings %u min_elev %d drLimit %u\n",
1132
(unsigned)_buffer.nav_settings.dynModel,
1133
(int)_buffer.nav_settings.minElev,
1134
(unsigned)_buffer.nav_settings.drLimit);
1135
_buffer.nav_settings.mask = 0;
1136
if (gps._navfilter != AP_GPS::GPS_ENGINE_NONE &&
1137
_buffer.nav_settings.dynModel != gps._navfilter) {
1138
// we've received the current nav settings, change the engine
1139
// settings and send them back
1140
Debug("Changing engine setting from %u to %u\n",
1141
(unsigned)_buffer.nav_settings.dynModel, (unsigned)gps._navfilter);
1142
_buffer.nav_settings.dynModel = gps._navfilter;
1143
_buffer.nav_settings.mask |= 1;
1144
}
1145
if (gps._min_elevation != -100 &&
1146
_buffer.nav_settings.minElev != gps._min_elevation) {
1147
Debug("Changing min elevation to %d\n", (int)gps._min_elevation);
1148
_buffer.nav_settings.minElev = gps._min_elevation;
1149
_buffer.nav_settings.mask |= 2;
1150
}
1151
if (_buffer.nav_settings.mask != 0) {
1152
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS,
1153
&_buffer.nav_settings,
1154
sizeof(_buffer.nav_settings));
1155
_unconfigured_messages |= CONFIG_NAV_SETTINGS;
1156
_cfg_needs_save = true;
1157
} else {
1158
_unconfigured_messages &= ~CONFIG_NAV_SETTINGS;
1159
}
1160
return false;
1161
1162
#if UBLOX_GNSS_SETTINGS
1163
case MSG_CFG_GNSS:
1164
if (params.gnss_mode != 0 && !supports_F9_config()) {
1165
struct ubx_cfg_gnss start_gnss = _buffer.gnss;
1166
uint8_t gnssCount = 0;
1167
Debug("Got GNSS Settings %u %u %u %u:\n",
1168
(unsigned)_buffer.gnss.msgVer,
1169
(unsigned)_buffer.gnss.numTrkChHw,
1170
(unsigned)_buffer.gnss.numTrkChUse,
1171
(unsigned)_buffer.gnss.numConfigBlocks);
1172
#if UBLOX_DEBUGGING
1173
for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
1174
Debug(" %u %u %u 0x%08x\n",
1175
(unsigned)_buffer.gnss.configBlock[i].gnssId,
1176
(unsigned)_buffer.gnss.configBlock[i].resTrkCh,
1177
(unsigned)_buffer.gnss.configBlock[i].maxTrkCh,
1178
(unsigned)_buffer.gnss.configBlock[i].flags);
1179
}
1180
#endif
1181
1182
for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) {
1183
if((params.gnss_mode & (1 << i)) && i != GNSS_SBAS) {
1184
gnssCount++;
1185
}
1186
}
1187
for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
1188
// Reserve an equal portion of channels for all enabled systems that supports it
1189
if(params.gnss_mode & (1 << _buffer.gnss.configBlock[i].gnssId)) {
1190
if(GNSS_SBAS !=_buffer.gnss.configBlock[i].gnssId && (_hardware_generation > UBLOX_M8 || GNSS_GALILEO !=_buffer.gnss.configBlock[i].gnssId)) {
1191
_buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
1192
_buffer.gnss.configBlock[i].maxTrkCh = _buffer.gnss.numTrkChHw;
1193
} else {
1194
if(GNSS_SBAS ==_buffer.gnss.configBlock[i].gnssId) {
1195
_buffer.gnss.configBlock[i].resTrkCh = 1;
1196
_buffer.gnss.configBlock[i].maxTrkCh = 3;
1197
}
1198
if(GNSS_GALILEO ==_buffer.gnss.configBlock[i].gnssId) {
1199
_buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
1200
_buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eight
1201
}
1202
}
1203
_buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001;
1204
} else {
1205
_buffer.gnss.configBlock[i].resTrkCh = 0;
1206
_buffer.gnss.configBlock[i].maxTrkCh = 0;
1207
_buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags & 0xFFFFFFFE;
1208
}
1209
}
1210
if (memcmp(&start_gnss, &_buffer.gnss, sizeof(start_gnss))) {
1211
_send_message(CLASS_CFG, MSG_CFG_GNSS, &_buffer.gnss, 4 + (8 * _buffer.gnss.numConfigBlocks));
1212
_unconfigured_messages |= CONFIG_GNSS;
1213
_cfg_needs_save = true;
1214
} else {
1215
_unconfigured_messages &= ~CONFIG_GNSS;
1216
}
1217
} else {
1218
_unconfigured_messages &= ~CONFIG_GNSS;
1219
}
1220
return false;
1221
#endif
1222
1223
case MSG_CFG_SBAS:
1224
if (gps._sbas_mode != AP_GPS::SBAS_Mode::DoNotChange) {
1225
Debug("Got SBAS settings %u %u %u 0x%x 0x%x\n",
1226
(unsigned)_buffer.sbas.mode,
1227
(unsigned)_buffer.sbas.usage,
1228
(unsigned)_buffer.sbas.maxSBAS,
1229
(unsigned)_buffer.sbas.scanmode2,
1230
(unsigned)_buffer.sbas.scanmode1);
1231
if (_buffer.sbas.mode != gps._sbas_mode) {
1232
_buffer.sbas.mode = gps._sbas_mode;
1233
_send_message(CLASS_CFG, MSG_CFG_SBAS,
1234
&_buffer.sbas,
1235
sizeof(_buffer.sbas));
1236
_unconfigured_messages |= CONFIG_SBAS;
1237
_cfg_needs_save = true;
1238
} else {
1239
_unconfigured_messages &= ~CONFIG_SBAS;
1240
}
1241
} else {
1242
_unconfigured_messages &= ~CONFIG_SBAS;
1243
}
1244
return false;
1245
case MSG_CFG_MSG:
1246
if(_payload_length == sizeof(ubx_cfg_msg_rate_6)) {
1247
// can't verify the setting without knowing the port
1248
// request the port again
1249
if(_ublox_port >= UBLOX_MAX_PORTS) {
1250
_request_port();
1251
return false;
1252
}
1253
_verify_rate(_buffer.msg_rate_6.msg_class, _buffer.msg_rate_6.msg_id,
1254
_buffer.msg_rate_6.rates[_ublox_port]);
1255
} else {
1256
_verify_rate(_buffer.msg_rate.msg_class, _buffer.msg_rate.msg_id,
1257
_buffer.msg_rate.rate);
1258
}
1259
return false;
1260
case MSG_CFG_PRT:
1261
_ublox_port = _buffer.prt.portID;
1262
return false;
1263
case MSG_CFG_RATE:
1264
if(_buffer.nav_rate.measure_rate_ms != params.rate_ms ||
1265
_buffer.nav_rate.nav_rate != 1 ||
1266
_buffer.nav_rate.timeref != 0) {
1267
_configure_rate();
1268
_unconfigured_messages |= CONFIG_RATE_NAV;
1269
_cfg_needs_save = true;
1270
} else {
1271
_unconfigured_messages &= ~CONFIG_RATE_NAV;
1272
}
1273
return false;
1274
1275
#if CONFIGURE_PPS_PIN
1276
case MSG_CFG_TP5: {
1277
// configure the PPS pin for 1Hz, zero delay
1278
Debug("Got TP5 ver=%u 0x%04x %u\n",
1279
(unsigned)_buffer.nav_tp5.version,
1280
(unsigned)_buffer.nav_tp5.flags,
1281
(unsigned)_buffer.nav_tp5.freqPeriod);
1282
#ifdef HAL_GPIO_PPS
1283
hal.gpio->attach_interrupt(HAL_GPIO_PPS, FUNCTOR_BIND_MEMBER(&AP_GPS_UBLOX::pps_interrupt, void, uint8_t, bool, uint32_t), AP_HAL::GPIO::INTERRUPT_FALLING);
1284
#endif
1285
const uint16_t desired_flags = 0x003f;
1286
const uint16_t desired_period_hz = _pps_freq;
1287
1288
if (_buffer.nav_tp5.flags != desired_flags ||
1289
_buffer.nav_tp5.freqPeriod != desired_period_hz) {
1290
_buffer.nav_tp5.tpIdx = 0;
1291
_buffer.nav_tp5.reserved1[0] = 0;
1292
_buffer.nav_tp5.reserved1[1] = 0;
1293
_buffer.nav_tp5.antCableDelay = 0;
1294
_buffer.nav_tp5.rfGroupDelay = 0;
1295
_buffer.nav_tp5.freqPeriod = desired_period_hz;
1296
_buffer.nav_tp5.freqPeriodLock = desired_period_hz;
1297
_buffer.nav_tp5.pulseLenRatio = 1;
1298
_buffer.nav_tp5.pulseLenRatioLock = 2;
1299
_buffer.nav_tp5.userConfigDelay = 0;
1300
_buffer.nav_tp5.flags = desired_flags;
1301
_send_message(CLASS_CFG, MSG_CFG_TP5,
1302
&_buffer.nav_tp5,
1303
sizeof(_buffer.nav_tp5));
1304
_unconfigured_messages |= CONFIG_TP5;
1305
_cfg_needs_save = true;
1306
} else {
1307
_unconfigured_messages &= ~CONFIG_TP5;
1308
}
1309
return false;
1310
}
1311
#endif // CONFIGURE_PPS_PIN
1312
case MSG_CFG_VALGET: {
1313
uint8_t cfg_len = _payload_length - sizeof(ubx_cfg_valget);
1314
const uint8_t *cfg_data = (const uint8_t *)(&_buffer) + sizeof(ubx_cfg_valget);
1315
while (cfg_len >= 5) {
1316
ConfigKey id;
1317
memcpy(&id, cfg_data, sizeof(uint32_t));
1318
cfg_len -= 4;
1319
cfg_data += 4;
1320
switch (id) {
1321
case ConfigKey::TMODE_MODE: {
1322
uint8_t mode = cfg_data[0];
1323
if (mode != 0) {
1324
// ask for mode 0, to disable TIME mode
1325
mode = 0;
1326
_configure_valset(ConfigKey::TMODE_MODE, &mode);
1327
_cfg_needs_save = true;
1328
_unconfigured_messages |= CONFIG_TMODE_MODE;
1329
} else {
1330
_unconfigured_messages &= ~CONFIG_TMODE_MODE;
1331
}
1332
break;
1333
}
1334
default:
1335
break;
1336
}
1337
// see if it is in active config list
1338
int8_t cfg_idx = find_active_config_index(id);
1339
if (cfg_idx >= 0) {
1340
CFG_Debug("valset(0x%lx): %u", uint32_t(id), (*cfg_data) & 0x1);
1341
const uint8_t key_size = config_key_size(id);
1342
if (cfg_len < key_size
1343
// for keys of length 1 only the LSB is significant
1344
|| (key_size == 1 && (active_config.list[cfg_idx].value & 0x1) != (*cfg_data & 0x1))
1345
|| memcmp(&active_config.list[cfg_idx].value, cfg_data, key_size) != 0) {
1346
_configure_valset(id, &active_config.list[cfg_idx].value, active_config.layers);
1347
_unconfigured_messages |= active_config.unconfig_bit;
1348
active_config.done_mask &= ~(1U << cfg_idx);
1349
active_config.set_index = cfg_idx;
1350
_cfg_needs_save = true;
1351
} else {
1352
active_config.done_mask |= (1U << cfg_idx);
1353
CFG_Debug("done %u mask=0x%x all_mask=0x%x",
1354
unsigned(cfg_idx),
1355
unsigned(active_config.done_mask),
1356
(1U<<active_config.count)-1);
1357
if (active_config.done_mask == (1U<<active_config.count)-1) {
1358
// all done!
1359
_unconfigured_messages &= ~active_config.unconfig_bit;
1360
}
1361
}
1362
if (active_config.fetch_index >= 0 &&
1363
active_config.fetch_index < active_config.count &&
1364
id == active_config.list[active_config.fetch_index].key) {
1365
active_config.fetch_index++;
1366
if (active_config.fetch_index < active_config.count) {
1367
_configure_valget(active_config.list[active_config.fetch_index].key);
1368
CFG_Debug("valget %d 0x%x", int(active_config.fetch_index),
1369
unsigned(active_config.list[active_config.fetch_index].key));
1370
}
1371
}
1372
} else {
1373
CFG_Debug("valget no active config for 0x%lx", (uint32_t)id);
1374
}
1375
1376
// step over the value
1377
uint8_t step_size = config_key_size(id);
1378
if (step_size == 0) {
1379
return false;
1380
}
1381
cfg_len -= step_size;
1382
cfg_data += step_size;
1383
}
1384
}
1385
}
1386
}
1387
1388
if (_class == CLASS_MON) {
1389
switch(_msg_id) {
1390
case MSG_MON_HW:
1391
if (_payload_length == 60 || _payload_length == 68) {
1392
log_mon_hw();
1393
}
1394
break;
1395
case MSG_MON_HW2:
1396
if (_payload_length == 28) {
1397
log_mon_hw2();
1398
}
1399
break;
1400
case MSG_MON_VER: {
1401
bool check_L1L5 = false;
1402
_have_version = true;
1403
strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
1404
strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
1405
void* mod = memmem(_buffer.mon_ver.extension, sizeof(_buffer.mon_ver.extension), "MOD=", 4);
1406
if (mod != nullptr) {
1407
strncpy(_module, (char*)mod+4, UBLOX_MODULE_LEN-1);
1408
}
1409
1410
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
1411
"u-blox %s%s%d HW: %s SW: %s",
1412
_module, mod != nullptr ? " " : "",
1413
state.instance + 1,
1414
_version.hwVersion,
1415
_version.swVersion);
1416
// check for F9 and M9. The F9 does not respond to SVINFO,
1417
// so we need to use MON_VER for hardware generation
1418
if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
1419
if (strncmp(_version.swVersion, "EXT CORE 1", 10) == 0) {
1420
// a F9
1421
if (_hardware_generation != UBLOX_F9) {
1422
// need to ensure time mode is correctly setup on F9
1423
_unconfigured_messages |= CONFIG_TMODE_MODE;
1424
}
1425
_hardware_generation = UBLOX_F9;
1426
_unconfigured_messages |= CONFIG_F9;
1427
_unconfigured_messages &= ~CONFIG_GNSS;
1428
if (strncmp(_module, "ZED-F9P", UBLOX_MODULE_LEN) == 0) {
1429
_hardware_variant = UBLOX_F9_ZED;
1430
} else if (strncmp(_module, "NEO-F9P", UBLOX_MODULE_LEN) == 0) {
1431
_hardware_variant = UBLOX_F9_NEO;
1432
}
1433
}
1434
if (strncmp(_version.swVersion, "EXT CORE 4", 10) == 0) {
1435
// a M9
1436
_hardware_generation = UBLOX_M9;
1437
}
1438
check_L1L5 = true;
1439
}
1440
// check for M10
1441
if (strncmp(_version.hwVersion, "000A0000", 8) == 0) {
1442
_hardware_generation = UBLOX_M10;
1443
_unconfigured_messages |= CONFIG_M10;
1444
// M10 does not support CONFIG_GNSS
1445
_unconfigured_messages &= ~CONFIG_GNSS;
1446
check_L1L5 = true;
1447
}
1448
if (check_L1L5) {
1449
// check if L1L5 in extension
1450
if (memmem(_buffer.mon_ver.extension, sizeof(_buffer.mon_ver.extension), "L1L5", 4) != nullptr) {
1451
supports_l5 = true;
1452
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "u-blox supports L5 Band");
1453
_unconfigured_messages |= CONFIG_L5;
1454
}
1455
}
1456
break;
1457
}
1458
default:
1459
unexpected_message();
1460
}
1461
return false;
1462
}
1463
1464
#if UBLOX_RXM_RAW_LOGGING
1465
if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAW && gps._raw_data != 0) {
1466
log_rxm_raw(_buffer.rxm_raw);
1467
return false;
1468
} else if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAWX && gps._raw_data != 0) {
1469
log_rxm_rawx(_buffer.rxm_rawx);
1470
return false;
1471
}
1472
#endif // UBLOX_RXM_RAW_LOGGING
1473
1474
#if UBLOX_TIM_TM2_LOGGING
1475
if ((_class == CLASS_TIM) && (_msg_id == MSG_TIM_TM2) && (_payload_length == 28)) {
1476
log_tim_tm2();
1477
return false;
1478
}
1479
#endif // UBLOX_TIM_TM2_LOGGING
1480
1481
if (_class != CLASS_NAV) {
1482
unexpected_message();
1483
return false;
1484
}
1485
1486
switch (_msg_id) {
1487
case MSG_POSLLH:
1488
Debug("MSG_POSLLH next_fix=%u", next_fix);
1489
if (havePvtMsg) {
1490
_unconfigured_messages |= CONFIG_RATE_POSLLH;
1491
break;
1492
}
1493
_check_new_itow(_buffer.posllh.itow);
1494
_last_pos_time = _buffer.posllh.itow;
1495
state.location.lng = _buffer.posllh.longitude;
1496
state.location.lat = _buffer.posllh.latitude;
1497
state.have_undulation = true;
1498
state.undulation = (_buffer.posllh.altitude_msl - _buffer.posllh.altitude_ellipsoid) * 0.001;
1499
set_alt_amsl_cm(state, _buffer.posllh.altitude_msl / 10);
1500
1501
state.status = next_fix;
1502
_new_position = true;
1503
state.horizontal_accuracy = _buffer.posllh.horizontal_accuracy*1.0e-3f;
1504
state.vertical_accuracy = _buffer.posllh.vertical_accuracy*1.0e-3f;
1505
state.have_horizontal_accuracy = true;
1506
state.have_vertical_accuracy = true;
1507
#if UBLOX_FAKE_3DLOCK
1508
state.location.lng = 1491652300L;
1509
state.location.lat = -353632610L;
1510
state.location.alt = 58400;
1511
state.vertical_accuracy = 0;
1512
state.horizontal_accuracy = 0;
1513
#endif
1514
break;
1515
case MSG_STATUS:
1516
Debug("MSG_STATUS fix_status=%u fix_type=%u",
1517
_buffer.status.fix_status,
1518
_buffer.status.fix_type);
1519
_check_new_itow(_buffer.status.itow);
1520
if (havePvtMsg) {
1521
_unconfigured_messages |= CONFIG_RATE_STATUS;
1522
break;
1523
}
1524
if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) {
1525
if( (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) &&
1526
(_buffer.status.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
1527
next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
1528
}else if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) {
1529
next_fix = AP_GPS::GPS_OK_FIX_3D;
1530
}else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) {
1531
next_fix = AP_GPS::GPS_OK_FIX_2D;
1532
}else{
1533
next_fix = AP_GPS::NO_FIX;
1534
state.status = AP_GPS::NO_FIX;
1535
}
1536
}else{
1537
next_fix = AP_GPS::NO_FIX;
1538
state.status = AP_GPS::NO_FIX;
1539
}
1540
#if UBLOX_FAKE_3DLOCK
1541
state.status = AP_GPS::GPS_OK_FIX_3D;
1542
next_fix = state.status;
1543
#endif
1544
break;
1545
case MSG_DOP:
1546
Debug("MSG_DOP");
1547
noReceivedHdop = false;
1548
_check_new_itow(_buffer.dop.itow);
1549
state.hdop = _buffer.dop.hDOP;
1550
state.vdop = _buffer.dop.vDOP;
1551
#if UBLOX_FAKE_3DLOCK
1552
state.hdop = 130;
1553
state.hdop = 170;
1554
#endif
1555
break;
1556
case MSG_SOL:
1557
Debug("MSG_SOL fix_status=%u fix_type=%u",
1558
_buffer.solution.fix_status,
1559
_buffer.solution.fix_type);
1560
_check_new_itow(_buffer.solution.itow);
1561
if (havePvtMsg) {
1562
state.time_week = _buffer.solution.week;
1563
break;
1564
}
1565
if (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) {
1566
if( (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) &&
1567
(_buffer.solution.fix_status & AP_GPS_UBLOX::NAV_STATUS_DGPS_USED)) {
1568
next_fix = AP_GPS::GPS_OK_FIX_3D_DGPS;
1569
}else if( _buffer.solution.fix_type == AP_GPS_UBLOX::FIX_3D) {
1570
next_fix = AP_GPS::GPS_OK_FIX_3D;
1571
}else if (_buffer.solution.fix_type == AP_GPS_UBLOX::FIX_2D) {
1572
next_fix = AP_GPS::GPS_OK_FIX_2D;
1573
}else{
1574
next_fix = AP_GPS::NO_FIX;
1575
state.status = AP_GPS::NO_FIX;
1576
}
1577
}else{
1578
next_fix = AP_GPS::NO_FIX;
1579
state.status = AP_GPS::NO_FIX;
1580
}
1581
if(noReceivedHdop) {
1582
state.hdop = _buffer.solution.position_DOP;
1583
}
1584
state.num_sats = _buffer.solution.satellites;
1585
if (next_fix >= AP_GPS::GPS_OK_FIX_2D) {
1586
state.last_gps_time_ms = AP_HAL::millis();
1587
state.time_week_ms = _buffer.solution.itow;
1588
state.time_week = _buffer.solution.week;
1589
}
1590
#if UBLOX_FAKE_3DLOCK
1591
next_fix = state.status;
1592
state.num_sats = 10;
1593
state.time_week = 1721;
1594
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
1595
state.last_gps_time_ms = AP_HAL::millis();
1596
state.hdop = 130;
1597
#endif
1598
break;
1599
1600
#if GPS_MOVING_BASELINE
1601
case MSG_RELPOSNED:
1602
{
1603
if (role != AP_GPS::GPS_ROLE_MB_ROVER) {
1604
// ignore RELPOSNED if not configured as a rover
1605
break;
1606
}
1607
// note that we require the yaw to come from a fixed solution, not a float solution
1608
// yaw from a float solution would only be acceptable with a very large separation between
1609
// GPS modules
1610
const uint32_t valid_mask = static_cast<uint32_t>(RELPOSNED::relPosHeadingValid) |
1611
static_cast<uint32_t>(RELPOSNED::relPosValid) |
1612
static_cast<uint32_t>(RELPOSNED::gnssFixOK) |
1613
static_cast<uint32_t>(RELPOSNED::isMoving) |
1614
static_cast<uint32_t>(RELPOSNED::carrSolnFixed);
1615
const uint32_t invalid_mask = static_cast<uint32_t>(RELPOSNED::refPosMiss) |
1616
static_cast<uint32_t>(RELPOSNED::refObsMiss) |
1617
static_cast<uint32_t>(RELPOSNED::carrSolnFloat);
1618
1619
_check_new_itow(_buffer.relposned.iTOW);
1620
if (_buffer.relposned.iTOW != _last_relposned_itow+200) {
1621
// useful for looking at packet loss on links
1622
MB_Debug("RELPOSNED ITOW %u %u\n", unsigned(_buffer.relposned.iTOW), unsigned(_last_relposned_itow));
1623
}
1624
_last_relposned_itow = _buffer.relposned.iTOW;
1625
MB_Debug("RELPOSNED flags: %lx valid: %lx invalid: %lx\n", _buffer.relposned.flags, valid_mask, invalid_mask);
1626
if (((_buffer.relposned.flags & valid_mask) == valid_mask) &&
1627
((_buffer.relposned.flags & invalid_mask) == 0)) {
1628
if (calculate_moving_base_yaw(_buffer.relposned.relPosHeading * 1e-5,
1629
_buffer.relposned.relPosLength * 0.01,
1630
_buffer.relposned.relPosD*0.01)) {
1631
state.have_gps_yaw_accuracy = true;
1632
state.gps_yaw_accuracy = _buffer.relposned.accHeading * 1e-5;
1633
_last_relposned_ms = AP_HAL::millis();
1634
}
1635
state.relPosHeading = _buffer.relposned.relPosHeading * 1e-5;
1636
state.relPosLength = _buffer.relposned.relPosLength * 0.01;
1637
state.relPosD = _buffer.relposned.relPosD * 0.01;
1638
state.accHeading = _buffer.relposned.accHeading * 1e-5;
1639
state.relposheading_ts = AP_HAL::millis();
1640
} else {
1641
state.have_gps_yaw_accuracy = false;
1642
}
1643
}
1644
break;
1645
#endif // GPS_MOVING_BASELINE
1646
1647
case MSG_PVT:
1648
Debug("MSG_PVT");
1649
1650
havePvtMsg = true;
1651
// position
1652
_check_new_itow(_buffer.pvt.itow);
1653
_last_pvt_itow = _buffer.pvt.itow;
1654
_last_pos_time = _buffer.pvt.itow;
1655
state.location.lng = _buffer.pvt.lon;
1656
state.location.lat = _buffer.pvt.lat;
1657
state.have_undulation = true;
1658
state.undulation = (_buffer.pvt.h_msl - _buffer.pvt.h_ellipsoid) * 0.001;
1659
set_alt_amsl_cm(state, _buffer.pvt.h_msl / 10);
1660
switch (_buffer.pvt.fix_type)
1661
{
1662
case 0:
1663
state.status = AP_GPS::NO_FIX;
1664
break;
1665
case 1:
1666
state.status = AP_GPS::NO_FIX;
1667
break;
1668
case 2:
1669
state.status = AP_GPS::GPS_OK_FIX_2D;
1670
break;
1671
case 3:
1672
state.status = AP_GPS::GPS_OK_FIX_3D;
1673
if (_buffer.pvt.flags & 0b00000010) // diffsoln
1674
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
1675
if (_buffer.pvt.flags & 0b01000000) // carrsoln - float
1676
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
1677
if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed
1678
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
1679
break;
1680
case 4:
1681
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
1682
"Unexpected state %d", _buffer.pvt.flags);
1683
state.status = AP_GPS::GPS_OK_FIX_3D;
1684
break;
1685
case 5:
1686
state.status = AP_GPS::NO_FIX;
1687
break;
1688
default:
1689
state.status = AP_GPS::NO_FIX;
1690
break;
1691
}
1692
next_fix = state.status;
1693
_new_position = true;
1694
state.horizontal_accuracy = _buffer.pvt.h_acc*1.0e-3f;
1695
state.vertical_accuracy = _buffer.pvt.v_acc*1.0e-3f;
1696
state.have_horizontal_accuracy = true;
1697
state.have_vertical_accuracy = true;
1698
// SVs
1699
state.num_sats = _buffer.pvt.num_sv;
1700
// velocity
1701
_last_vel_time = _buffer.pvt.itow;
1702
state.ground_speed = _buffer.pvt.gspeed*0.001f; // m/s
1703
state.ground_course = wrap_360(_buffer.pvt.head_mot * 1.0e-5f); // Heading 2D deg * 100000
1704
state.have_vertical_velocity = true;
1705
state.velocity.x = _buffer.pvt.velN * 0.001f;
1706
state.velocity.y = _buffer.pvt.velE * 0.001f;
1707
state.velocity.z = _buffer.pvt.velD * 0.001f;
1708
state.have_speed_accuracy = true;
1709
state.speed_accuracy = _buffer.pvt.s_acc*0.001f;
1710
_new_speed = true;
1711
// dop
1712
if(noReceivedHdop) {
1713
state.hdop = _buffer.pvt.p_dop;
1714
state.vdop = _buffer.pvt.p_dop;
1715
}
1716
1717
if (_buffer.pvt.fix_type >= 2) {
1718
state.last_gps_time_ms = AP_HAL::millis();
1719
}
1720
1721
// time
1722
state.time_week_ms = _buffer.pvt.itow;
1723
#if UBLOX_FAKE_3DLOCK
1724
state.location.lng = 1491652300L;
1725
state.location.lat = -353632610L;
1726
state.location.alt = 58400;
1727
state.vertical_accuracy = 0;
1728
state.horizontal_accuracy = 0;
1729
state.status = AP_GPS::GPS_OK_FIX_3D;
1730
state.num_sats = 10;
1731
state.time_week = 1721;
1732
state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
1733
state.last_gps_time_ms = AP_HAL::millis();
1734
state.hdop = 130;
1735
state.speed_accuracy = 0;
1736
next_fix = state.status;
1737
#endif
1738
break;
1739
case MSG_TIMEGPS:
1740
Debug("MSG_TIMEGPS");
1741
_check_new_itow(_buffer.timegps.itow);
1742
if (_buffer.timegps.valid & UBX_TIMEGPS_VALID_WEEK_MASK) {
1743
state.time_week = _buffer.timegps.week;
1744
}
1745
break;
1746
case MSG_VELNED:
1747
Debug("MSG_VELNED");
1748
if (havePvtMsg) {
1749
_unconfigured_messages |= CONFIG_RATE_VELNED;
1750
break;
1751
}
1752
_check_new_itow(_buffer.velned.itow);
1753
_last_vel_time = _buffer.velned.itow;
1754
state.ground_speed = _buffer.velned.speed_2d*0.01f; // m/s
1755
state.ground_course = wrap_360(_buffer.velned.heading_2d * 1.0e-5f); // Heading 2D deg * 100000
1756
state.have_vertical_velocity = true;
1757
state.velocity.x = _buffer.velned.ned_north * 0.01f;
1758
state.velocity.y = _buffer.velned.ned_east * 0.01f;
1759
state.velocity.z = _buffer.velned.ned_down * 0.01f;
1760
velocity_to_speed_course(state);
1761
state.have_speed_accuracy = true;
1762
state.speed_accuracy = _buffer.velned.speed_accuracy*0.01f;
1763
#if UBLOX_FAKE_3DLOCK
1764
state.speed_accuracy = 0;
1765
#endif
1766
_new_speed = true;
1767
break;
1768
case MSG_NAV_SVINFO:
1769
{
1770
Debug("MSG_NAV_SVINFO\n");
1771
static const uint8_t HardwareGenerationMask = 0x07;
1772
_check_new_itow(_buffer.svinfo_header.itow);
1773
_hardware_generation = _buffer.svinfo_header.globalFlags & HardwareGenerationMask;
1774
switch (_hardware_generation) {
1775
case UBLOX_5:
1776
case UBLOX_6:
1777
// only 7 and newer support CONFIG_GNSS
1778
_unconfigured_messages &= ~CONFIG_GNSS;
1779
break;
1780
case UBLOX_7:
1781
case UBLOX_M8:
1782
#if UBLOX_SPEED_CHANGE
1783
port->begin(4000000U);
1784
Debug("Changed speed to 4Mhz for SPI-driven UBlox\n");
1785
#endif
1786
break;
1787
default:
1788
hal.console->printf("Wrong Ublox Hardware Version%u\n", _hardware_generation);
1789
break;
1790
};
1791
_unconfigured_messages &= ~CONFIG_VERSION;
1792
/* We don't need that anymore */
1793
_configure_message_rate(CLASS_NAV, MSG_NAV_SVINFO, 0);
1794
break;
1795
}
1796
default:
1797
Debug("Unexpected NAV message 0x%02x", (unsigned)_msg_id);
1798
if (++_disable_counter == 0) {
1799
Debug("Disabling NAV message 0x%02x", (unsigned)_msg_id);
1800
_configure_message_rate(CLASS_NAV, _msg_id, 0);
1801
}
1802
return false;
1803
}
1804
1805
if (state.have_gps_yaw) {
1806
// when we are a rover we want to ensure we have both the new
1807
// PVT and the new RELPOSNED message so that we give a
1808
// consistent view
1809
if (AP_HAL::millis() - _last_relposned_ms > 400) {
1810
// we have stopped receiving valid RELPOSNED messages, disable yaw reporting
1811
state.have_gps_yaw = false;
1812
} else if (_last_relposned_itow != _last_pvt_itow) {
1813
// wait until ITOW matches
1814
return false;
1815
}
1816
}
1817
1818
// we only return true when we get new position and speed data
1819
// this ensures we don't use stale data
1820
if (_new_position && _new_speed && _last_vel_time == _last_pos_time) {
1821
_new_speed = _new_position = false;
1822
return true;
1823
}
1824
return false;
1825
}
1826
1827
/*
1828
* handle pps interrupt
1829
*/
1830
#ifdef HAL_GPIO_PPS
1831
void
1832
AP_GPS_UBLOX::pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us)
1833
{
1834
_last_pps_time_us = AP_HAL::micros64();
1835
}
1836
1837
void
1838
AP_GPS_UBLOX::set_pps_desired_freq(uint8_t freq)
1839
{
1840
_pps_freq = freq;
1841
_unconfigured_messages |= CONFIG_TP5;
1842
}
1843
#endif
1844
1845
1846
// UBlox auto configuration
1847
1848
/*
1849
* update checksum for a set of bytes
1850
*/
1851
void
1852
AP_GPS_UBLOX::_update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b)
1853
{
1854
while (len--) {
1855
ck_a += *data;
1856
ck_b += ck_a;
1857
data++;
1858
}
1859
}
1860
1861
1862
/*
1863
* send a ublox message
1864
*/
1865
bool
1866
AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size)
1867
{
1868
if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) {
1869
return false;
1870
}
1871
struct ubx_header header;
1872
uint8_t ck_a=0, ck_b=0;
1873
header.preamble1 = PREAMBLE1;
1874
header.preamble2 = PREAMBLE2;
1875
header.msg_class = msg_class;
1876
header.msg_id = msg_id;
1877
header.length = size;
1878
1879
_update_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b);
1880
_update_checksum((uint8_t *)msg, size, ck_a, ck_b);
1881
1882
port->write((const uint8_t *)&header, sizeof(header));
1883
port->write((const uint8_t *)msg, size);
1884
port->write((const uint8_t *)&ck_a, 1);
1885
port->write((const uint8_t *)&ck_b, 1);
1886
return true;
1887
}
1888
1889
/*
1890
* requests the given message rate for a specific message class
1891
* and msg_id
1892
* returns true if it sent the request, false if waiting on knowing the port
1893
*/
1894
bool
1895
AP_GPS_UBLOX::_request_message_rate(uint8_t msg_class, uint8_t msg_id)
1896
{
1897
// Without knowing what communication port is being used it isn't possible to verify
1898
// always ensure we have a port before sending the request
1899
if(_ublox_port >= UBLOX_MAX_PORTS) {
1900
_request_port();
1901
return false;
1902
} else {
1903
struct ubx_cfg_msg msg;
1904
msg.msg_class = msg_class;
1905
msg.msg_id = msg_id;
1906
return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
1907
}
1908
}
1909
1910
/*
1911
* configure a UBlox GPS for the given message rate for a specific
1912
* message class and msg_id
1913
*/
1914
bool
1915
AP_GPS_UBLOX::_configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
1916
{
1917
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_msg_rate)+2)) {
1918
return false;
1919
}
1920
1921
struct ubx_cfg_msg_rate msg;
1922
msg.msg_class = msg_class;
1923
msg.msg_id = msg_id;
1924
msg.rate = rate;
1925
return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
1926
}
1927
1928
/*
1929
* configure F9/M10 based key/value pair - VALSET
1930
*/
1931
bool
1932
AP_GPS_UBLOX::_configure_valset(ConfigKey key, const void *value, uint8_t layers)
1933
{
1934
if (!supports_F9_config()) {
1935
return false;
1936
}
1937
1938
const uint8_t len = config_key_size(key);
1939
struct ubx_cfg_valset msg {};
1940
uint8_t buf[sizeof(msg)+len];
1941
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(buf)+2)) {
1942
return false;
1943
}
1944
msg.version = 1;
1945
msg.layers = layers;
1946
msg.transaction = 0;
1947
msg.key = uint32_t(key);
1948
memcpy(buf, &msg, sizeof(msg));
1949
memcpy(&buf[sizeof(msg)], value, len);
1950
auto ret = _send_message(CLASS_CFG, MSG_CFG_VALSET, buf, sizeof(buf));
1951
return ret;
1952
}
1953
1954
/*
1955
* configure F9 based key/value pair - VALGET
1956
*/
1957
bool
1958
AP_GPS_UBLOX::_configure_valget(ConfigKey key)
1959
{
1960
if (!supports_F9_config()) {
1961
return false;
1962
}
1963
struct {
1964
struct ubx_cfg_valget msg;
1965
ConfigKey key;
1966
} msg {};
1967
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(msg)+2)) {
1968
return false;
1969
}
1970
msg.msg.version = 0;
1971
msg.msg.layers = 0; // ram
1972
msg.key = key;
1973
return _send_message(CLASS_CFG, MSG_CFG_VALGET, &msg, sizeof(msg));
1974
}
1975
1976
/*
1977
* configure F9 based key/value pair for a complete configuration set
1978
*
1979
* this method requests each configuration variable from the GPS.
1980
* When we handle the reply in _parse_gps we may then choose to set a
1981
* MSG_CFG_VALSET back to the GPS if we don't like its response.
1982
*/
1983
bool
1984
AP_GPS_UBLOX::_configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit, uint8_t layers)
1985
{
1986
active_config.list = list;
1987
active_config.count = count;
1988
active_config.done_mask = 0;
1989
active_config.unconfig_bit = unconfig_bit;
1990
active_config.layers = layers;
1991
// we start by fetching multiple values at once (with fetch_index
1992
// -1) then if we get a NACK for VALGET we switch to fetching one
1993
// value at a time. This copes with the M10S which can only fetch
1994
// one value at a time
1995
active_config.fetch_index = -1;
1996
1997
uint8_t buf[sizeof(ubx_cfg_valget)+count*sizeof(ConfigKey)];
1998
struct ubx_cfg_valget msg {};
1999
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(buf)+2)) {
2000
return false;
2001
}
2002
msg.version = 0;
2003
msg.layers = 0; // ram
2004
memcpy(buf, &msg, sizeof(msg));
2005
for (uint8_t i=0; i<count; i++) {
2006
memcpy(&buf[sizeof(msg)+i*sizeof(ConfigKey)], &list[i].key, sizeof(ConfigKey));
2007
}
2008
return _send_message(CLASS_CFG, MSG_CFG_VALGET, buf, sizeof(buf));
2009
}
2010
2011
/*
2012
* configure F9 based key/value pair for a complete configuration set
2013
*
2014
* this method sends all the key/value pairs in a block, but makes no attempt to check
2015
* the results. Sending in a block is necessary for updates such as GNSS where certain
2016
* combinations are invalid and setting one at a time will not produce the correct result
2017
* if the result needs to be validated then a subsequent _configure_config_set() can be
2018
* issued which will get all the values and reset those that are not properly updated.
2019
*/
2020
bool
2021
AP_GPS_UBLOX::_configure_list_valset(const config_list *list, uint8_t count, uint8_t layers)
2022
{
2023
if (!supports_F9_config()) {
2024
return false;
2025
}
2026
2027
struct ubx_cfg_valset msg {};
2028
uint8_t buf[sizeof(msg)+sizeof(config_list)*count];
2029
if (port->txspace() < (uint16_t)(sizeof(struct ubx_header)+sizeof(buf)+2)) {
2030
return false;
2031
}
2032
msg.version = 1;
2033
msg.layers = layers;
2034
msg.transaction = 0;
2035
uint32_t msg_len = sizeof(msg) - sizeof(msg.key);
2036
memcpy(buf, &msg, msg_len);
2037
2038
uint8_t* payload = &buf[msg_len];
2039
for (uint8_t i=0; i<count; i++) {
2040
const uint8_t len = config_key_size(list[i].key);
2041
memcpy(payload, &list[i].key, sizeof(ConfigKey));
2042
payload += sizeof(ConfigKey);
2043
msg_len += sizeof(ConfigKey);
2044
memcpy(payload, &list[i].value, len);
2045
payload += len;
2046
msg_len += len;
2047
}
2048
2049
auto ret = _send_message(CLASS_CFG, MSG_CFG_VALSET, buf, msg_len);
2050
return ret;
2051
}
2052
2053
/*
2054
* save gps configurations to non-volatile memory sent until the call of
2055
* this message
2056
*/
2057
void
2058
AP_GPS_UBLOX::_save_cfg()
2059
{
2060
static const ubx_cfg_cfg save_cfg {
2061
clearMask: 0,
2062
saveMask: SAVE_CFG_ALL,
2063
loadMask: 0
2064
};
2065
_send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
2066
_last_cfg_sent_time = AP_HAL::millis();
2067
_num_cfg_save_tries++;
2068
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
2069
"GPS %d: u-blox saving config",
2070
state.instance + 1);
2071
}
2072
2073
/*
2074
detect a Ublox GPS. Adds one byte, and returns true if the stream
2075
matches a UBlox
2076
*/
2077
bool
2078
AP_GPS_UBLOX::_detect(struct UBLOX_detect_state &state, uint8_t data)
2079
{
2080
reset:
2081
switch (state.step) {
2082
case 1:
2083
if (PREAMBLE2 == data) {
2084
state.step++;
2085
break;
2086
}
2087
state.step = 0;
2088
FALLTHROUGH;
2089
case 0:
2090
if (PREAMBLE1 == data)
2091
state.step++;
2092
break;
2093
case 2:
2094
state.step++;
2095
state.ck_b = state.ck_a = data;
2096
break;
2097
case 3:
2098
state.step++;
2099
state.ck_b += (state.ck_a += data);
2100
break;
2101
case 4:
2102
state.step++;
2103
state.ck_b += (state.ck_a += data);
2104
state.payload_length = data;
2105
break;
2106
case 5:
2107
state.step++;
2108
state.ck_b += (state.ck_a += data);
2109
state.payload_counter = 0;
2110
break;
2111
case 6:
2112
state.ck_b += (state.ck_a += data);
2113
if (++state.payload_counter == state.payload_length)
2114
state.step++;
2115
break;
2116
case 7:
2117
state.step++;
2118
if (state.ck_a != data) {
2119
state.step = 0;
2120
goto reset;
2121
}
2122
break;
2123
case 8:
2124
state.step = 0;
2125
if (state.ck_b == data) {
2126
// a valid UBlox packet
2127
return true;
2128
} else {
2129
goto reset;
2130
}
2131
}
2132
return false;
2133
}
2134
2135
void
2136
AP_GPS_UBLOX::_request_version(void)
2137
{
2138
_send_message(CLASS_MON, MSG_MON_VER, nullptr, 0);
2139
}
2140
2141
void
2142
AP_GPS_UBLOX::_configure_rate(void)
2143
{
2144
struct ubx_cfg_nav_rate msg;
2145
// require a minimum measurement rate of 5Hz
2146
msg.measure_rate_ms = gps.get_rate_ms(state.instance);
2147
msg.nav_rate = 1;
2148
msg.timeref = 0; // UTC time
2149
_send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));
2150
}
2151
2152
static const char *reasons[] = {"navigation rate",
2153
"posllh rate",
2154
"status rate",
2155
"solution rate",
2156
"velned rate",
2157
"dop rate",
2158
"hw monitor rate",
2159
"hw2 monitor rate",
2160
"raw rate",
2161
"version",
2162
"navigation settings",
2163
"GNSS settings",
2164
"SBAS settings",
2165
"PVT rate",
2166
"time pulse settings",
2167
"TIMEGPS rate",
2168
"Time mode settings",
2169
"RTK MB",
2170
"TIM TM2",
2171
"F9",
2172
"M10",
2173
"L5 Enable Disable"};
2174
2175
static_assert((1 << ARRAY_SIZE(reasons)) == CONFIG_LAST, "UBLOX: Missing configuration description");
2176
2177
void
2178
AP_GPS_UBLOX::broadcast_configuration_failure_reason(void) const {
2179
for (uint8_t i = 0; i < ARRAY_SIZE(reasons); i++) {
2180
if (_unconfigured_messages & (1 << i)) {
2181
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: u-blox %s configuration 0x%02x",
2182
(unsigned int)(state.instance + 1), reasons[i], (unsigned int)_unconfigured_messages);
2183
break;
2184
}
2185
}
2186
}
2187
2188
/*
2189
return velocity lag in seconds
2190
*/
2191
bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
2192
{
2193
switch (_hardware_generation) {
2194
case UBLOX_UNKNOWN_HARDWARE_GENERATION:
2195
lag_sec = 0.22f;
2196
// always bail out in this case, it's used to indicate we have yet to receive a valid
2197
// hardware generation, however the user may have inhibited us detecting the generation
2198
// so if we aren't allowed to do configuration, we will accept this as the default delay
2199
return gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE;
2200
case UBLOX_5:
2201
case UBLOX_6:
2202
default:
2203
lag_sec = 0.22f;
2204
break;
2205
case UBLOX_7:
2206
case UBLOX_M8:
2207
// based on flight logs the 7 and 8 series seem to produce about 120ms lag
2208
lag_sec = 0.12f;
2209
break;
2210
case UBLOX_F9:
2211
case UBLOX_M9:
2212
case UBLOX_M10:
2213
// F9 lag not verified yet from flight log, but likely to be at least
2214
// as good as M8
2215
lag_sec = 0.12f;
2216
#if GPS_MOVING_BASELINE
2217
if (role == AP_GPS::GPS_ROLE_MB_BASE ||
2218
role == AP_GPS::GPS_ROLE_MB_ROVER) {
2219
// the moving baseline rover will lag about 40ms from the
2220
// base. We need to provide the more conservative value to
2221
// ensure that the EKF allocates a larger enough buffer
2222
lag_sec += 0.04;
2223
}
2224
#endif
2225
break;
2226
};
2227
return true;
2228
}
2229
2230
#if HAL_LOGGING_ENABLED
2231
void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
2232
{
2233
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
2234
2235
if (_have_version) {
2236
AP::logger().Write_MessageF("u-blox %d HW: %s SW: %s",
2237
state.instance+1,
2238
_version.hwVersion,
2239
_version.swVersion);
2240
}
2241
}
2242
#endif
2243
2244
// uBlox specific check_new_itow(), handling message length
2245
void AP_GPS_UBLOX::_check_new_itow(uint32_t itow)
2246
{
2247
check_new_itow(itow, _payload_length + sizeof(ubx_header) + 2);
2248
}
2249
2250
// support for retrieving RTCMv3 data from a moving baseline base
2251
bool AP_GPS_UBLOX::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)
2252
{
2253
#if GPS_MOVING_BASELINE
2254
if (rtcm3_parser) {
2255
len = rtcm3_parser->get_len(bytes);
2256
return len > 0;
2257
}
2258
#endif
2259
return false;
2260
}
2261
2262
// clear previous RTCM3 packet
2263
void AP_GPS_UBLOX::clear_RTCMV3(void)
2264
{
2265
#if GPS_MOVING_BASELINE
2266
if (rtcm3_parser) {
2267
rtcm3_parser->clear_packet();
2268
}
2269
#endif
2270
}
2271
2272
// ublox specific healthy checks
2273
bool AP_GPS_UBLOX::is_healthy(void) const
2274
{
2275
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2276
if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
2277
// allow for fake ublox moving baseline
2278
return true;
2279
}
2280
#endif
2281
#if GPS_MOVING_BASELINE
2282
if ((role == AP_GPS::GPS_ROLE_MB_BASE ||
2283
role == AP_GPS::GPS_ROLE_MB_ROVER) &&
2284
!supports_F9_config()) {
2285
// need F9 or above for moving baseline
2286
return false;
2287
}
2288
if (role == AP_GPS::GPS_ROLE_MB_BASE && rtcm3_parser == nullptr && !mb_use_uart2()) {
2289
// we haven't initialised RTCMv3 parser
2290
return false;
2291
}
2292
#endif
2293
return true;
2294
}
2295
2296
// populate config_GNSS with F9 GNSS configuration
2297
uint8_t AP_GPS_UBLOX::populate_F9_gnss(void)
2298
{
2299
uint8_t cfg_count = 0;
2300
2301
if (params.gnss_mode == 0) {
2302
_unconfigured_messages &= ~CONFIG_F9;
2303
last_configured_gnss = params.gnss_mode;
2304
return 0;
2305
}
2306
2307
if ((_unconfigured_messages & CONFIG_F9) != 0) {
2308
// ZED-F9P defaults are
2309
// GPS L1C/A+L2C(ZED)
2310
// SBAS L1C/A
2311
// GALILEO E1+E5B(ZED)+E5A(NEO)
2312
// BEIDOU B1+B2(ZED)+B2A(NEO)
2313
// QZSS L1C/A+L2C(ZED)+L5(NEO)
2314
// GLONASS L1+L2(ZED)
2315
// IMES not supported
2316
// GPS and QZSS should be enabled/disabled together, but we will leave them alone
2317
// QZSS and SBAS can only be enabled if GPS is enabled
2318
2319
if (config_GNSS == nullptr) {
2320
config_GNSS = (config_list*)calloc(UBLOX_MAX_GNSS_CONFIG_BLOCKS*3, sizeof(config_list));
2321
}
2322
2323
if (config_GNSS == nullptr) {
2324
return 0;
2325
}
2326
2327
uint8_t gnss_mode = params.gnss_mode;
2328
gnss_mode |= 1U<<GNSS_GPS;
2329
gnss_mode |= 1U<<GNSS_QZSS;
2330
gnss_mode &= ~(1U<<GNSS_IMES);
2331
params.gnss_mode.set_and_save(gnss_mode);
2332
2333
for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) {
2334
bool ena = gnss_mode & (1U<<i);
2335
switch (i) {
2336
case GNSS_SBAS:
2337
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_SBAS_ENA, ena };
2338
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_SBAS_L1CA_ENA, ena };
2339
break;
2340
case GNSS_GALILEO:
2341
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GAL_ENA, ena };
2342
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GAL_E1_ENA, ena };
2343
if (_hardware_variant == UBLOX_F9_ZED) {
2344
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GAL_E5B_ENA, ena };
2345
} else {
2346
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GAL_E5A_ENA, ena };
2347
}
2348
break;
2349
case GNSS_BEIDOU:
2350
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_BDS_ENA, ena };
2351
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_BDS_B1_ENA, ena };
2352
if (_hardware_variant == UBLOX_F9_ZED) {
2353
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_BDS_B2_ENA, ena };
2354
} else {
2355
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_BDS_B2A_ENA, ena };
2356
}
2357
break;
2358
case GNSS_GLONASS:
2359
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GLO_ENA, ena };
2360
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GLO_L1_ENA, ena };
2361
if (_hardware_variant == UBLOX_F9_ZED) {
2362
config_GNSS[cfg_count++] = { ConfigKey::CFG_SIGNAL_GLO_L2_ENA, ena };
2363
}
2364
break;
2365
// not supported or leave alone
2366
case GNSS_IMES:
2367
case GNSS_QZSS:
2368
case GNSS_GPS:
2369
break;
2370
}
2371
}
2372
}
2373
2374
last_configured_gnss = params.gnss_mode;
2375
2376
return cfg_count;
2377
}
2378
2379
// return true if GPS is capable of F9 config
2380
bool AP_GPS_UBLOX::supports_F9_config(void) const
2381
{
2382
return _hardware_generation == UBLOX_F9 || _hardware_generation == UBLOX_M10;
2383
}
2384
2385
// return true if GPS is capable of F9 config
2386
bool AP_GPS_UBLOX::is_gnss_key(ConfigKey key) const
2387
{
2388
return (unsigned(key) & 0xFFFF0000) == 0x10310000;
2389
}
2390
2391
#endif
2392
2393