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.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
#include "AP_GPS_config.h"
16
17
#if AP_GPS_ENABLED
18
19
#include "AP_GPS.h"
20
21
#include <AP_Common/AP_Common.h>
22
#include <AP_HAL/AP_HAL.h>
23
#include <AP_Math/AP_Math.h>
24
#include <AP_Notify/AP_Notify.h>
25
#include <GCS_MAVLink/GCS.h>
26
#include <AP_BoardConfig/AP_BoardConfig.h>
27
#include <AP_RTC/AP_RTC.h>
28
#include <climits>
29
#include <AP_SerialManager/AP_SerialManager.h>
30
31
#include "AP_GPS_NOVA.h"
32
#include "AP_GPS_Blended.h"
33
#include "AP_GPS_ERB.h"
34
#include "AP_GPS_GSOF.h"
35
#include "AP_GPS_NMEA.h"
36
#include "AP_GPS_SBF.h"
37
#include "AP_GPS_SBP.h"
38
#include "AP_GPS_SBP2.h"
39
#include "AP_GPS_SIRF.h"
40
#include "AP_GPS_UBLOX.h"
41
#include "AP_GPS_MAV.h"
42
#include "AP_GPS_MSP.h"
43
#include "AP_GPS_ExternalAHRS.h"
44
#include "GPS_Backend.h"
45
#if HAL_SIM_GPS_ENABLED
46
#include "AP_GPS_SITL.h"
47
#endif
48
49
#if HAL_ENABLE_DRONECAN_DRIVERS
50
#include <AP_CANManager/AP_CANManager.h>
51
#include <AP_DroneCAN/AP_DroneCAN.h>
52
#include "AP_GPS_DroneCAN.h"
53
#endif
54
55
#include <AP_AHRS/AP_AHRS.h>
56
#include <AP_Logger/AP_Logger.h>
57
#include "AP_GPS_FixType.h"
58
59
#if AP_GPS_RTCM_DECODE_ENABLED
60
#include "RTCM3_Parser.h"
61
#endif
62
63
#if !AP_GPS_BLENDED_ENABLED
64
#if defined(GPS_BLENDED_INSTANCE)
65
#error GPS_BLENDED_INSTANCE should not be defined when AP_GPS_BLENDED_ENABLED is false
66
#endif
67
#endif
68
69
#define GPS_RTK_INJECT_TO_ALL 127
70
#ifndef GPS_MAX_RATE_MS
71
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
72
#endif
73
#define GPS_BAUD_TIME_MS 1200
74
#define GPS_TIMEOUT_MS 4000u
75
76
extern const AP_HAL::HAL &hal;
77
78
// baudrates to try to detect GPSes with
79
const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U, 460800U};
80
81
// initialisation blobs to send to the GPS to try to get it into the
82
// right mode.
83
const char AP_GPS::_initialisation_blob[] =
84
#if AP_GPS_UBLOX_ENABLED
85
UBLOX_SET_BINARY_230400
86
#endif
87
#if AP_GPS_SIRF_ENABLED
88
SIRF_SET_BINARY
89
#endif
90
#if AP_GPS_NMEA_UNICORE_ENABLED
91
NMEA_UNICORE_SETUP
92
#endif
93
"" // to compile we need *some_initialiser if all backends compiled out
94
;
95
96
#if HAL_GCS_ENABLED
97
// ensure that our GPS_Status enumeration is 1:1 with the mavlink
98
// numbers of the same fix type. This allows us to do a simple cast
99
// from one to the other when sending GPS mavlink messages, rather
100
// than having some sort of mapping function from our internal
101
// enumeration into the mavlink enumeration. Doing things this way
102
// has two advantages - in the future we could add that mapping
103
// function and change our enumeration, and the other is that it
104
// allows us to build the GPS library without having the mavlink
105
// headers built (for example, in AP_Periph we shouldn't need mavlink
106
// headers).
107
static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint32_t)GPS_FIX_TYPE_NO_GPS, "NO_GPS incorrect");
108
static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint32_t)GPS_FIX_TYPE_NO_FIX, "NO_FIX incorrect");
109
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint32_t)GPS_FIX_TYPE_2D_FIX, "FIX_2D incorrect");
110
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint32_t)GPS_FIX_TYPE_3D_FIX, "FIX_3D incorrect");
111
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint32_t)GPS_FIX_TYPE_DGPS, "FIX_DGPS incorrect");
112
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t)GPS_FIX_TYPE_RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
113
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");
114
#endif
115
116
// ensure that our own enum-class status is equivalent to the
117
// ArduPilot-scoped AP_GPS_FixType enumeration:
118
static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint8_t)AP_GPS_FixType::NO_GPS, "NO_GPS incorrect");
119
static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint8_t)AP_GPS_FixType::NONE, "NO_FIX incorrect");
120
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint8_t)AP_GPS_FixType::FIX_2D, "FIX_2D incorrect");
121
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint8_t)AP_GPS_FixType::FIX_3D, "FIX_3D incorrect");
122
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint8_t)AP_GPS_FixType::DGPS, "FIX_DGPS incorrect");
123
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint8_t)AP_GPS_FixType::RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
124
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint8_t)AP_GPS_FixType::RTK_FIXED, "FIX_RTK_FIXED incorrect");
125
126
AP_GPS *AP_GPS::_singleton;
127
128
// table of user settable parameters
129
const AP_Param::GroupInfo AP_GPS::var_info[] = {
130
131
// 0 was GPS_TYPE
132
133
// 1 was GPS_TYPE2
134
135
// @Param: _NAVFILTER
136
// @DisplayName: Navigation filter setting
137
// @Description: Navigation filter engine setting
138
// @Values: 0:Portable,2:Stationary,3:Pedestrian,4:Automotive,5:Sea,6:Airborne1G,7:Airborne2G,8:Airborne4G
139
// @User: Advanced
140
AP_GROUPINFO("_NAVFILTER", 2, AP_GPS, _navfilter, GPS_ENGINE_AIRBORNE_4G),
141
142
#if GPS_MAX_RECEIVERS > 1
143
// @Param: _AUTO_SWITCH
144
// @DisplayName: Automatic Switchover Setting
145
// @Description: Automatic switchover to GPS reporting best lock, 1:UseBest selects the GPS with highest status, if both are equal the GPS with highest satellite count is used 4:Use primary if 3D fix or better, will revert to 'UseBest' behaviour if 3D fix is lost on primary
146
// @Values: 0:Use primary, 1:UseBest, 2:Blend, 4:Use primary if 3D fix or better
147
// @User: Advanced
148
AP_GROUPINFO("_AUTO_SWITCH", 3, AP_GPS, _auto_switch, (int8_t)GPSAutoSwitch::USE_BEST),
149
#endif
150
151
// 4 was _MIN_GPS, removed Feb 2024
152
153
// @Param: _SBAS_MODE
154
// @DisplayName: SBAS Mode
155
// @Description: This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
156
// @Values: 0:Disabled,1:Enabled,2:NoChange
157
// @User: Advanced
158
AP_GROUPINFO("_SBAS_MODE", 5, AP_GPS, _sbas_mode, 2),
159
160
// @Param: _MIN_ELEV
161
// @DisplayName: Minimum elevation
162
// @Description: This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
163
// @Range: -100 90
164
// @Units: deg
165
// @User: Advanced
166
AP_GROUPINFO("_MIN_ELEV", 6, AP_GPS, _min_elevation, -100),
167
168
// @Param: _INJECT_TO
169
// @DisplayName: Destination for GPS_INJECT_DATA MAVLink packets
170
// @Description: The GGS can send raw serial packets to inject data to multiple GPSes.
171
// @Values: 0:send to first GPS,1:send to 2nd GPS,127:send to all
172
// @User: Advanced
173
AP_GROUPINFO("_INJECT_TO", 7, AP_GPS, _inject_to, GPS_RTK_INJECT_TO_ALL),
174
175
#if AP_GPS_SBP2_ENABLED || AP_GPS_SBP_ENABLED
176
// @Param: _SBP_LOGMASK
177
// @DisplayName: Swift Binary Protocol Logging Mask
178
// @Description: Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
179
// @Values: 0:None (0x0000),-1:All (0xFFFF),-256:External only (0xFF00)
180
// @User: Advanced
181
AP_GROUPINFO("_SBP_LOGMASK", 8, AP_GPS, _sbp_logmask, -256),
182
#endif //AP_GPS_SBP2_ENABLED || AP_GPS_SBP_ENABLED
183
184
// @Param: _RAW_DATA
185
// @DisplayName: Raw data logging
186
// @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
187
// @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
188
// @RebootRequired: True
189
// @User: Advanced
190
AP_GROUPINFO("_RAW_DATA", 9, AP_GPS, _raw_data, 0),
191
192
// 10 was GPS_GNSS_MODE
193
194
// @Param: _SAVE_CFG
195
// @DisplayName: Save GPS configuration
196
// @Description: Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
197
// @Values: 0:Do not save config,1:Save config,2:Save only when needed
198
// @User: Advanced
199
AP_GROUPINFO("_SAVE_CFG", 11, AP_GPS, _save_config, 2),
200
201
// 12 was GPS_GNSS_MODE2
202
203
// @Param: _AUTO_CONFIG
204
// @DisplayName: Automatic GPS configuration
205
// @Description: Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
206
// @Values: 0:Disables automatic configuration,1:Enable automatic configuration for Serial GPSes only,2:Enable automatic configuration for DroneCAN as well
207
// @User: Advanced
208
AP_GROUPINFO("_AUTO_CONFIG", 13, AP_GPS, _auto_config, 1),
209
210
// 14 was GPS_RATE_MS
211
212
// 15 was GPS_RATE_MS2
213
214
// 16 was GPS_POS1
215
216
// 17 was GPS_POS2
217
218
// 18 was GPS_DELAY_MS
219
220
// 19 was GPS_DELAY_MS2
221
222
#if AP_GPS_BLENDED_ENABLED
223
// @Param: _BLEND_MASK
224
// @DisplayName: Multi GPS Blending Mask
225
// @Description: Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2(Blend)
226
// @Bitmask: 0:Horiz Pos,1:Vert Pos,2:Speed
227
// @User: Advanced
228
AP_GROUPINFO("_BLEND_MASK", 20, AP_GPS, _blend_mask, 5),
229
230
// @Param: _BLEND_TC
231
// @DisplayName: Blending time constant
232
// @Description: Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
233
// @Units: s
234
// @Range: 5.0 30.0
235
// @User: Advanced
236
// Had key 21, no longer used
237
#endif
238
239
// @Param: _DRV_OPTIONS
240
// @DisplayName: driver options
241
// @Description: Additional backend specific options
242
// @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL, 5:Override GPS satellite health of L5 band from L1 health, 6:Enable RTCM full parse even for a single channel, 7:Disable automatic full RTCM parsing when RTCM seen on more than one channel
243
// @User: Advanced
244
AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0),
245
246
// 23 was GPS_COM_PORT
247
248
// 24 was GPS_COM_PORT2
249
250
// 25 was GPS_MB1_*
251
252
// 26 was GPS_MB2_*
253
254
#if GPS_MAX_RECEIVERS > 1
255
// @Param: _PRIMARY
256
// @DisplayName: Primary GPS
257
// @Description: This GPS will be used when GPS_AUTO_SWITCH is 0 and used preferentially with GPS_AUTO_SWITCH = 4.
258
// @Increment: 1
259
// @Values: 0:FirstGPS, 1:SecondGPS
260
// @User: Advanced
261
AP_GROUPINFO("_PRIMARY", 27, AP_GPS, _primary, 0),
262
#endif
263
264
// 28 was GPS_CAN_NODEID1
265
266
// 29 was GPS_CAN_NODEID2
267
268
// 30 was GPS1_CAN_OVRIDE
269
270
// 31 was GPS2_CAN_OVRIDE
271
272
// @Group: 1_
273
// @Path: AP_GPS_Params.cpp
274
AP_SUBGROUPINFO(params[0], "1_", 32, AP_GPS, AP_GPS::Params),
275
276
#if GPS_MAX_RECEIVERS > 1
277
// @Group: 2_
278
// @Path: AP_GPS_Params.cpp
279
AP_SUBGROUPINFO(params[1], "2_", 33, AP_GPS, AP_GPS::Params),
280
#endif
281
282
AP_GROUPEND
283
};
284
285
// constructor
286
AP_GPS::AP_GPS()
287
{
288
static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3),
289
"GPS initilisation blob is too large to be completely sent before the baud rate changes");
290
291
AP_Param::setup_object_defaults(this, var_info);
292
293
if (_singleton != nullptr) {
294
AP_HAL::panic("AP_GPS must be singleton");
295
}
296
_singleton = this;
297
}
298
299
// return true if a specific type of GPS uses a UART
300
bool AP_GPS::needs_uart(GPS_Type type) const
301
{
302
switch (type) {
303
case GPS_TYPE_NONE:
304
case GPS_TYPE_HIL:
305
case GPS_TYPE_UAVCAN:
306
case GPS_TYPE_UAVCAN_RTK_BASE:
307
case GPS_TYPE_UAVCAN_RTK_ROVER:
308
case GPS_TYPE_MAV:
309
case GPS_TYPE_MSP:
310
case GPS_TYPE_EXTERNAL_AHRS:
311
return false;
312
default:
313
break;
314
}
315
return true;
316
}
317
318
/// Startup initialisation.
319
void AP_GPS::init()
320
{
321
// set the default for the first GPS according to define:
322
params[0].type.set_default(HAL_GPS1_TYPE_DEFAULT);
323
324
convert_parameters();
325
326
// Set new primary param based on old auto_switch use second option
327
if ((_auto_switch.get() == 3) && !_primary.configured()) {
328
_primary.set_and_save(1);
329
_auto_switch.set_and_save(0);
330
}
331
332
// search for serial ports with gps protocol
333
const auto &serial_manager = AP::serialmanager();
334
uint8_t uart_idx = 0;
335
for (uint8_t i=0; i<ARRAY_SIZE(params); i++) {
336
if (needs_uart(params[i].type)) {
337
_port[i] = serial_manager.find_serial(AP_SerialManager::SerialProtocol_GPS, uart_idx);
338
uart_idx++;
339
}
340
}
341
_last_instance_swap_ms = 0;
342
343
// prep the state instance fields
344
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
345
state[i].instance = i;
346
}
347
348
// sanity check update rate
349
for (uint8_t i=0; i<ARRAY_SIZE(params); i++) {
350
auto &rate_ms = params[i].rate_ms;
351
if (rate_ms <= 0 || rate_ms > GPS_MAX_RATE_MS) {
352
rate_ms.set(GPS_MAX_RATE_MS);
353
}
354
}
355
356
// create the blended instance if appropriate:
357
#if AP_GPS_BLENDED_ENABLED
358
drivers[GPS_BLENDED_INSTANCE] = NEW_NOTHROW AP_GPS_Blended(*this, params[GPS_BLENDED_INSTANCE], state[GPS_BLENDED_INSTANCE], timing[GPS_BLENDED_INSTANCE]);
359
#endif
360
}
361
362
void AP_GPS::convert_parameters()
363
{
364
// find GPS's top level key
365
uint16_t k_param_gps_key;
366
if (!AP_Param::find_top_level_key_by_pointer(this, k_param_gps_key)) {
367
return;
368
}
369
370
// table parameters to convert without scaling
371
static const AP_Param::ConversionInfo conversion_info[] {
372
// PARAMETER_CONVERSION - Added: Mar-2024 for 4.6
373
{ k_param_gps_key, 0, AP_PARAM_INT8, "GPS1_TYPE" },
374
{ k_param_gps_key, 1, AP_PARAM_INT8, "GPS2_TYPE" },
375
{ k_param_gps_key, 10, AP_PARAM_INT8, "GPS1_GNSS_MODE" },
376
{ k_param_gps_key, 12, AP_PARAM_INT8, "GPS2_GNSS_MODE" },
377
{ k_param_gps_key, 14, AP_PARAM_INT16, "GPS1_RATE_MS" },
378
{ k_param_gps_key, 15, AP_PARAM_INT16, "GPS2_RATE_MS" },
379
{ k_param_gps_key, 16, AP_PARAM_VECTOR3F, "GPS1_POS" },
380
{ k_param_gps_key, 17, AP_PARAM_VECTOR3F, "GPS2_POS" },
381
{ k_param_gps_key, 18, AP_PARAM_INT16, "GPS1_DELAY_MS" },
382
{ k_param_gps_key, 19, AP_PARAM_INT16, "GPS2_DELAY_MS" },
383
#if AP_GPS_SBF_ENABLED
384
{ k_param_gps_key, 23, AP_PARAM_INT8, "GPS1_COM_PORT" },
385
{ k_param_gps_key, 24, AP_PARAM_INT8, "GPS2_COM_PORT" },
386
#endif
387
388
#if HAL_ENABLE_DRONECAN_DRIVERS
389
{ k_param_gps_key, 28, AP_PARAM_INT32, "GPS1_CAN_NODEID" },
390
{ k_param_gps_key, 29, AP_PARAM_INT32, "GPS2_CAN_NODEID" },
391
{ k_param_gps_key, 30, AP_PARAM_INT32, "GPS1_CAN_OVRIDE" },
392
{ k_param_gps_key, 31, AP_PARAM_INT32, "GPS2_CAN_OVRIDE" },
393
#endif
394
};
395
AP_Param::convert_old_parameters(conversion_info, ARRAY_SIZE(conversion_info));
396
397
#if GPS_MOVING_BASELINE
398
// convert old MovingBaseline parameters
399
// PARAMETER_CONVERSION - Added: Mar-2024 for 4.6
400
for (uint8_t i=0; i<MIN(2, GPS_MAX_RECEIVERS); i++) {
401
// the old _MB parameters were 25 and 26:
402
const uint8_t old_index = 25 + i;
403
AP_Param::convert_class(k_param_gps_key, &params[i].mb_params, params[i].mb_params.var_info, old_index, false);
404
}
405
#endif // GPS_MOVING_BASELINE
406
}
407
408
// return number of active GPS sensors. Note that if the first GPS
409
// is not present but the 2nd is then we return 2. Note that a blended
410
// GPS solution is treated as an additional sensor.
411
uint8_t AP_GPS::num_sensors(void) const
412
{
413
#if AP_GPS_BLENDED_ENABLED
414
if (_output_is_blended) {
415
return num_instances+1;
416
}
417
#endif
418
return num_instances;
419
}
420
421
bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const
422
{
423
if (state[instance].have_speed_accuracy) {
424
sacc = state[instance].speed_accuracy;
425
return true;
426
}
427
return false;
428
}
429
430
bool AP_GPS::horizontal_accuracy(uint8_t instance, float &hacc) const
431
{
432
if (state[instance].have_horizontal_accuracy) {
433
hacc = state[instance].horizontal_accuracy;
434
return true;
435
}
436
return false;
437
}
438
439
bool AP_GPS::vertical_accuracy(uint8_t instance, float &vacc) const
440
{
441
if (state[instance].have_vertical_accuracy) {
442
vacc = state[instance].vertical_accuracy;
443
return true;
444
}
445
return false;
446
}
447
448
AP_GPS::CovarianceType AP_GPS::position_covariance(const uint8_t instance, Matrix3f& cov) const
449
{
450
AP_GPS::CovarianceType cov_type = AP_GPS::CovarianceType::UNKNOWN;
451
cov.zero();
452
float hacc, vacc;
453
if (horizontal_accuracy(instance, hacc) && vertical_accuracy(instance, vacc))
454
{
455
cov_type = AP_GPS::CovarianceType::DIAGONAL_KNOWN;
456
const auto hacc_variance = hacc * hacc;
457
cov[0][0] = hacc_variance;
458
cov[1][1] = hacc_variance;
459
cov[2][2] = vacc * vacc;
460
}
461
// There may be a receiver that implements hdop+vdop but not accuracy
462
// If so, there could be a condition here to attempt to calculate it
463
464
return cov_type;
465
}
466
467
468
/**
469
convert GPS week and milliseconds to unix epoch in milliseconds
470
*/
471
uint64_t AP_GPS::istate_time_to_epoch_ms(uint16_t gps_week, uint32_t gps_ms)
472
{
473
uint64_t fix_time_ms = UNIX_OFFSET_MSEC + gps_week * AP_MSEC_PER_WEEK + gps_ms;
474
return fix_time_ms;
475
}
476
477
/**
478
calculate current time since the unix epoch in microseconds
479
*/
480
uint64_t AP_GPS::time_epoch_usec(uint8_t instance) const
481
{
482
const GPS_State &istate = state[instance];
483
if ((istate.last_gps_time_ms == 0 && istate.last_corrected_gps_time_us == 0) || istate.time_week == 0) {
484
return 0;
485
}
486
uint64_t fix_time_ms;
487
// add in the time since the last fix message
488
if (istate.last_corrected_gps_time_us != 0) {
489
fix_time_ms = istate_time_to_epoch_ms(istate.time_week, drivers[instance]->get_last_itow_ms());
490
return (fix_time_ms*1000ULL) + (AP_HAL::micros64() - istate.last_corrected_gps_time_us);
491
} else {
492
fix_time_ms = istate_time_to_epoch_ms(istate.time_week, istate.time_week_ms);
493
return (fix_time_ms + (AP_HAL::millis() - istate.last_gps_time_ms)) * 1000ULL;
494
}
495
}
496
497
/**
498
calculate last message time since the unix epoch in microseconds
499
*/
500
uint64_t AP_GPS::last_message_epoch_usec(uint8_t instance) const
501
{
502
const GPS_State &istate = state[instance];
503
if (istate.time_week == 0) {
504
return 0;
505
}
506
return istate_time_to_epoch_ms(istate.time_week, drivers[instance]->get_last_itow_ms()) * 1000ULL;
507
}
508
509
/*
510
send some more initialisation string bytes if there is room in the
511
UART transmit buffer
512
*/
513
void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
514
{
515
initblob_state[instance].blob = _blob;
516
initblob_state[instance].remaining = size;
517
}
518
519
/*
520
initialise state for sending binary blob initialisation strings. We
521
may choose different blobs not just based on type but also based on
522
parameters.
523
*/
524
void AP_GPS::send_blob_start(uint8_t instance)
525
{
526
const auto type = params[instance].type;
527
528
#if AP_GPS_UBLOX_ENABLED
529
if (type == GPS_TYPE_UBLOX && option_set(DriverOptions::UBX_Use115200)) {
530
static const char blob[] = UBLOX_SET_BINARY_115200;
531
send_blob_start(instance, blob, sizeof(blob));
532
return;
533
}
534
#endif // AP_GPS_UBLOX_ENABLED
535
536
#if GPS_MOVING_BASELINE && AP_GPS_UBLOX_ENABLED
537
if ((type == GPS_TYPE_UBLOX_RTK_BASE ||
538
type == GPS_TYPE_UBLOX_RTK_ROVER) &&
539
!option_set(DriverOptions::UBX_MBUseUart2)) {
540
// we use 460800 when doing moving baseline as we need
541
// more bandwidth. We don't do this if using UART2, as
542
// in that case the RTCMv3 data doesn't go over the
543
// link to the flight controller
544
static const char blob[] = UBLOX_SET_BINARY_460800;
545
send_blob_start(instance, blob, sizeof(blob));
546
return;
547
}
548
#endif
549
550
// the following devices don't have init blobs:
551
const char *blob = nullptr;
552
uint32_t blob_size = 0;
553
switch (GPS_Type(type)) {
554
#if AP_GPS_SBF_ENABLED
555
case GPS_TYPE_SBF:
556
case GPS_TYPE_SBF_DUAL_ANTENNA:
557
#endif //AP_GPS_SBF_ENABLED
558
#if AP_GPS_GSOF_ENABLED
559
case GPS_TYPE_GSOF:
560
#endif //AP_GPS_GSOF_ENABLED
561
#if AP_GPS_NOVA_ENABLED
562
case GPS_TYPE_NOVA:
563
#endif //AP_GPS_NOVA_ENABLED
564
#if HAL_SIM_GPS_ENABLED
565
case GPS_TYPE_SITL:
566
#endif // HAL_SIM_GPS_ENABLED
567
// none of these GPSs have initialisation blobs
568
break;
569
default:
570
// send combined initialisation blob, on the assumption that the
571
// GPS units will parse what they need and ignore the data they
572
// don't understand:
573
blob = _initialisation_blob;
574
blob_size = sizeof(_initialisation_blob);
575
break;
576
}
577
578
send_blob_start(instance, blob, blob_size);
579
}
580
581
/*
582
send some more initialisation string bytes if there is room in the
583
UART transmit buffer
584
*/
585
void AP_GPS::send_blob_update(uint8_t instance)
586
{
587
// exit immediately if no uart for this instance
588
if (_port[instance] == nullptr) {
589
return;
590
}
591
592
if (initblob_state[instance].remaining == 0) {
593
return;
594
}
595
596
// see if we can write some more of the initialisation blob
597
const uint16_t n = MIN(_port[instance]->txspace(),
598
initblob_state[instance].remaining);
599
const size_t written = _port[instance]->write((const uint8_t*)initblob_state[instance].blob, n);
600
initblob_state[instance].blob += written;
601
initblob_state[instance].remaining -= written;
602
}
603
604
/*
605
run detection step for one GPS instance. If this finds a GPS then it
606
will fill in drivers[instance] and change state[instance].status
607
from NO_GPS to NO_FIX.
608
*/
609
void AP_GPS::detect_instance(uint8_t instance)
610
{
611
const uint32_t now = AP_HAL::millis();
612
613
state[instance].status = NO_GPS;
614
state[instance].hdop = GPS_UNKNOWN_DOP;
615
state[instance].vdop = GPS_UNKNOWN_DOP;
616
617
AP_GPS_Backend *new_gps = _detect_instance(instance);
618
if (new_gps == nullptr) {
619
return;
620
}
621
622
state[instance].status = NO_FIX;
623
drivers[instance] = new_gps;
624
timing[instance].last_message_time_ms = now;
625
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
626
627
new_gps->broadcast_gps_type();
628
}
629
630
/*
631
run detection step for one GPS instance. If this finds a GPS then it
632
will return it - otherwise nullptr
633
*/
634
AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
635
{
636
struct detect_state *dstate = &detect_state[instance];
637
638
const auto type = params[instance].type;
639
640
switch (GPS_Type(type)) {
641
// user has to explicitly set the MAV type, do not use AUTO
642
// do not try to detect the MAV type, assume it's there
643
case GPS_TYPE_MAV:
644
#if AP_GPS_MAV_ENABLED
645
dstate->auto_detected_baud = false; // specified, not detected
646
return NEW_NOTHROW AP_GPS_MAV(*this, params[instance], state[instance], nullptr);
647
#endif //AP_GPS_MAV_ENABLED
648
649
// user has to explicitly set the UAVCAN type, do not use AUTO
650
case GPS_TYPE_UAVCAN:
651
case GPS_TYPE_UAVCAN_RTK_BASE:
652
case GPS_TYPE_UAVCAN_RTK_ROVER:
653
#if AP_GPS_DRONECAN_ENABLED
654
dstate->auto_detected_baud = false; // specified, not detected
655
return AP_GPS_DroneCAN::probe(*this, state[instance]);
656
#endif
657
return nullptr; // We don't do anything here if UAVCAN is not supported
658
#if HAL_MSP_GPS_ENABLED
659
case GPS_TYPE_MSP:
660
dstate->auto_detected_baud = false; // specified, not detected
661
return NEW_NOTHROW AP_GPS_MSP(*this, params[instance], state[instance], nullptr);
662
#endif
663
#if HAL_EXTERNAL_AHRS_ENABLED
664
case GPS_TYPE_EXTERNAL_AHRS:
665
if (AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::GPS) >= 0) {
666
dstate->auto_detected_baud = false; // specified, not detected
667
return NEW_NOTHROW AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr);
668
}
669
break;
670
#endif
671
#if AP_GPS_GSOF_ENABLED
672
case GPS_TYPE_GSOF:
673
dstate->auto_detected_baud = false; // specified, not detected
674
return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], _port[instance]);
675
#endif //AP_GPS_GSOF_ENABLED
676
default:
677
break;
678
}
679
680
if (_port[instance] == nullptr) {
681
// UART not available
682
return nullptr;
683
}
684
685
// all remaining drivers automatically cycle through baud rates to detect
686
// the correct baud rate, and should have the selected baud broadcast
687
dstate->auto_detected_baud = true;
688
const uint32_t now = AP_HAL::millis();
689
690
if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
691
// try the next baud rate
692
// incrementing like this will skip the first element in array of bauds
693
// this is okay, and relied upon
694
if (dstate->probe_baud == 0) {
695
dstate->probe_baud = _port[instance]->get_baud_rate();
696
} else {
697
dstate->current_baud++;
698
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
699
dstate->current_baud = 0;
700
}
701
dstate->probe_baud = _baudrates[dstate->current_baud];
702
}
703
uint16_t rx_size=0, tx_size=0;
704
if (type == GPS_TYPE_UBLOX_RTK_ROVER) {
705
tx_size = 2048;
706
}
707
if (type == GPS_TYPE_UBLOX_RTK_BASE) {
708
rx_size = 2048;
709
}
710
_port[instance]->begin(dstate->probe_baud, rx_size, tx_size);
711
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
712
dstate->last_baud_change_ms = now;
713
714
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
715
send_blob_start(instance);
716
}
717
}
718
719
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
720
send_blob_update(instance);
721
}
722
723
switch (GPS_Type(type)) {
724
#if AP_GPS_SBF_ENABLED
725
// by default the sbf/trimble gps outputs no data on its port, until configured.
726
case GPS_TYPE_SBF:
727
case GPS_TYPE_SBF_DUAL_ANTENNA:
728
return NEW_NOTHROW AP_GPS_SBF(*this, params[instance], state[instance], _port[instance]);
729
#endif //AP_GPS_SBF_ENABLED
730
#if AP_GPS_NOVA_ENABLED
731
case GPS_TYPE_NOVA:
732
return NEW_NOTHROW AP_GPS_NOVA(*this, params[instance], state[instance], _port[instance]);
733
#endif //AP_GPS_NOVA_ENABLED
734
735
#if HAL_SIM_GPS_ENABLED
736
case GPS_TYPE_SITL:
737
return NEW_NOTHROW AP_GPS_SITL(*this, params[instance], state[instance], _port[instance]);
738
#endif // HAL_SIM_GPS_ENABLED
739
740
default:
741
break;
742
}
743
744
if (initblob_state[instance].remaining != 0) {
745
// don't run detection engines if we haven't sent out the initblobs
746
return nullptr;
747
}
748
749
uint16_t bytecount = MIN(8192U, _port[instance]->available());
750
751
while (bytecount-- > 0) {
752
const uint8_t data = _port[instance]->read();
753
(void)data; // if all backends are compiled out then "data" is unused
754
755
#if AP_GPS_UBLOX_ENABLED
756
if ((type == GPS_TYPE_AUTO ||
757
type == GPS_TYPE_UBLOX) &&
758
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
759
(_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) ||
760
_baudrates[dstate->current_baud] == 230400) &&
761
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
762
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], GPS_ROLE_NORMAL);
763
}
764
765
const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800;
766
if ((type == GPS_TYPE_UBLOX_RTK_BASE ||
767
type == GPS_TYPE_UBLOX_RTK_ROVER) &&
768
_baudrates[dstate->current_baud] == ublox_mb_required_baud &&
769
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
770
GPS_Role role;
771
if (type == GPS_TYPE_UBLOX_RTK_BASE) {
772
role = GPS_ROLE_MB_BASE;
773
} else {
774
role = GPS_ROLE_MB_ROVER;
775
}
776
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], _port[instance], role);
777
}
778
#endif // AP_GPS_UBLOX_ENABLED
779
#if AP_GPS_SBP2_ENABLED
780
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
781
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
782
return NEW_NOTHROW AP_GPS_SBP2(*this, params[instance], state[instance], _port[instance]);
783
}
784
#endif //AP_GPS_SBP2_ENABLED
785
#if AP_GPS_SBP_ENABLED
786
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
787
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
788
return NEW_NOTHROW AP_GPS_SBP(*this, params[instance], state[instance], _port[instance]);
789
}
790
#endif //AP_GPS_SBP_ENABLED
791
#if AP_GPS_SIRF_ENABLED
792
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SIRF) &&
793
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
794
return NEW_NOTHROW AP_GPS_SIRF(*this, params[instance], state[instance], _port[instance]);
795
}
796
#endif
797
#if AP_GPS_ERB_ENABLED
798
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_ERB) &&
799
AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
800
return NEW_NOTHROW AP_GPS_ERB(*this, params[instance], state[instance], _port[instance]);
801
}
802
#endif // AP_GPS_ERB_ENABLED
803
#if AP_GPS_NMEA_ENABLED
804
if ((type == GPS_TYPE_NMEA ||
805
type == GPS_TYPE_HEMI ||
806
#if AP_GPS_NMEA_UNICORE_ENABLED
807
type == GPS_TYPE_UNICORE_NMEA ||
808
type == GPS_TYPE_UNICORE_MOVINGBASE_NMEA ||
809
#endif
810
type == GPS_TYPE_ALLYSTAR) &&
811
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
812
return NEW_NOTHROW AP_GPS_NMEA(*this, params[instance], state[instance], _port[instance]);
813
}
814
#endif //AP_GPS_NMEA_ENABLED
815
}
816
817
return nullptr;
818
}
819
820
AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
821
{
822
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
823
return drivers[instance]->highest_supported_status();
824
}
825
return AP_GPS::GPS_OK_FIX_3D;
826
}
827
828
#if HAL_LOGGING_ENABLED
829
bool AP_GPS::should_log() const
830
{
831
AP_Logger *logger = AP_Logger::get_singleton();
832
if (logger == nullptr) {
833
return false;
834
}
835
if (_log_gps_bit == (uint32_t)-1) {
836
return false;
837
}
838
if (!logger->should_log(_log_gps_bit)) {
839
return false;
840
}
841
return true;
842
}
843
#endif
844
845
846
/*
847
update one GPS instance. This should be called at 10Hz or greater
848
*/
849
void AP_GPS::update_instance(uint8_t instance)
850
{
851
const auto type = params[instance].type;
852
if (type == GPS_TYPE_HIL) {
853
// in HIL, leave info alone
854
return;
855
}
856
if (type == GPS_TYPE_NONE) {
857
// not enabled
858
state[instance].status = NO_GPS;
859
state[instance].hdop = GPS_UNKNOWN_DOP;
860
state[instance].vdop = GPS_UNKNOWN_DOP;
861
return;
862
}
863
if (locked_ports & (1U<<instance)) {
864
// the port is locked by another driver
865
return;
866
}
867
868
if (drivers[instance] == nullptr) {
869
// we don't yet know the GPS type of this one, or it has timed
870
// out and needs to be re-initialised
871
detect_instance(instance);
872
return;
873
}
874
875
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
876
send_blob_update(instance);
877
}
878
879
// we have an active driver for this instance
880
bool result = drivers[instance]->read();
881
uint32_t tnow = AP_HAL::millis();
882
883
// if we did not get a message, and the idle timer of 2 seconds
884
// has expired, re-initialise the GPS. This will cause GPS
885
// detection to run again
886
bool data_should_be_logged = false;
887
if (!result) {
888
if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
889
memset((void *)&state[instance], 0, sizeof(state[instance]));
890
state[instance].instance = instance;
891
state[instance].hdop = GPS_UNKNOWN_DOP;
892
state[instance].vdop = GPS_UNKNOWN_DOP;
893
timing[instance].last_message_time_ms = tnow;
894
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
895
// do not try to detect again if type is MAV or UAVCAN
896
if (type == GPS_TYPE_MAV ||
897
type == GPS_TYPE_UAVCAN ||
898
type == GPS_TYPE_UAVCAN_RTK_BASE ||
899
type == GPS_TYPE_UAVCAN_RTK_ROVER) {
900
state[instance].status = NO_FIX;
901
} else {
902
// free the driver before we run the next detection, so we
903
// don't end up with two allocated at any time
904
delete drivers[instance];
905
drivers[instance] = nullptr;
906
state[instance].status = NO_GPS;
907
}
908
// log this data as a "flag" that the GPS is no longer
909
// valid (see PR#8144)
910
data_should_be_logged = true;
911
}
912
} else {
913
if (state[instance].corrected_timestamp_updated) {
914
// set the timestamp for this messages based on
915
// set_uart_timestamp() or per specific transport in backend
916
// , if available
917
tnow = state[instance].last_corrected_gps_time_us/1000U;
918
state[instance].corrected_timestamp_updated = false;
919
}
920
921
// announce the GPS type once
922
if (!state[instance].announced_detection) {
923
state[instance].announced_detection = true;
924
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: detected %s", instance + 1, drivers[instance]->name());
925
}
926
927
// delta will only be correct after parsing two messages
928
timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
929
timing[instance].last_message_time_ms = tnow;
930
// if GPS disabled for flight testing then don't update fix timing value
931
if (state[instance].status >= GPS_OK_FIX_2D && !_force_disable_gps) {
932
timing[instance].last_fix_time_ms = tnow;
933
}
934
935
data_should_be_logged = true;
936
}
937
938
#if GPS_MAX_RECEIVERS > 1
939
if (drivers[instance] && type == GPS_TYPE_UBLOX_RTK_BASE) {
940
// see if a moving baseline base has some RTCMv3 data
941
// which we need to pass along to the rover
942
const uint8_t *rtcm_data;
943
uint16_t rtcm_len;
944
if (drivers[instance]->get_RTCMV3(rtcm_data, rtcm_len)) {
945
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
946
if (i != instance && params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {
947
// pass the data to the rover
948
inject_data(i, rtcm_data, rtcm_len);
949
drivers[instance]->clear_RTCMV3();
950
break;
951
}
952
}
953
}
954
}
955
#endif
956
957
if (data_should_be_logged) {
958
// keep count of delayed frames and average frame delay for health reporting
959
const uint16_t gps_max_delta_ms = 245; // 200 ms (5Hz) + 45 ms buffer
960
GPS_timing &t = timing[instance];
961
962
if (t.delta_time_ms > gps_max_delta_ms) {
963
t.delayed_count++;
964
} else {
965
t.delayed_count = 0;
966
}
967
if (t.delta_time_ms < 2000) {
968
if (t.average_delta_ms <= 0) {
969
t.average_delta_ms = t.delta_time_ms;
970
} else {
971
t.average_delta_ms = 0.98f * t.average_delta_ms + 0.02f * t.delta_time_ms;
972
}
973
}
974
}
975
976
#if HAL_LOGGING_ENABLED
977
if (data_should_be_logged && should_log()) {
978
Write_GPS(instance);
979
}
980
#else
981
(void)data_should_be_logged;
982
#endif
983
984
#if AP_RTC_ENABLED
985
if (state[instance].status >= GPS_OK_FIX_3D) {
986
const uint64_t now = time_epoch_usec(instance);
987
if (now != 0) {
988
AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
989
}
990
}
991
#endif
992
}
993
994
995
#if GPS_MOVING_BASELINE
996
bool AP_GPS::get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading)
997
{
998
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
999
if (drivers[i] &&
1000
state[i].relposheading_ts != 0 &&
1001
AP_HAL::millis() - state[i].relposheading_ts < 500) {
1002
relPosHeading = state[i].relPosHeading;
1003
relPosLength = state[i].relPosLength;
1004
relPosD = state[i].relPosD;
1005
accHeading = state[i].accHeading;
1006
timestamp = state[i].relposheading_ts;
1007
return true;
1008
}
1009
}
1010
return false;
1011
}
1012
1013
bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)
1014
{
1015
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1016
if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {
1017
return drivers[i]->get_RTCMV3(bytes, len);
1018
}
1019
}
1020
return false;
1021
}
1022
1023
void AP_GPS::clear_RTCMV3()
1024
{
1025
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1026
if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {
1027
drivers[i]->clear_RTCMV3();
1028
}
1029
}
1030
}
1031
1032
/*
1033
inject Moving Baseline Data messages.
1034
*/
1035
void AP_GPS::inject_MBL_data(uint8_t* data, uint16_t length)
1036
{
1037
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1038
if (params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {
1039
// pass the data to the rover
1040
inject_data(i, data, length);
1041
break;
1042
}
1043
}
1044
}
1045
#endif //#if GPS_MOVING_BASELINE
1046
1047
/*
1048
update all GPS instances
1049
*/
1050
void AP_GPS::update(void)
1051
{
1052
WITH_SEMAPHORE(rsem);
1053
1054
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1055
update_instance(i);
1056
}
1057
1058
// calculate number of instances
1059
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1060
if (drivers[i] != nullptr) {
1061
num_instances = i+1;
1062
}
1063
}
1064
1065
#if GPS_MAX_RECEIVERS > 1
1066
#if HAL_LOGGING_ENABLED
1067
const uint8_t old_primary = primary_instance;
1068
#endif
1069
update_primary();
1070
#if HAL_LOGGING_ENABLED
1071
if (primary_instance != old_primary) {
1072
AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);
1073
}
1074
#endif // HAL_LOGING_ENABLED
1075
#endif // GPS_MAX_RECEIVERS > 1
1076
1077
#ifndef HAL_BUILD_AP_PERIPH
1078
// update notify with gps status. We always base this on the primary_instance
1079
AP_Notify::flags.gps_status = state[primary_instance].status;
1080
AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats;
1081
#endif
1082
}
1083
1084
/*
1085
update primary GPS instance
1086
*/
1087
#if GPS_MAX_RECEIVERS > 1
1088
void AP_GPS::update_primary(void)
1089
{
1090
#if AP_GPS_BLENDED_ENABLED
1091
/*
1092
if blending is requested, attempt to calculate weighting for
1093
each GPS
1094
we do not do blending if using moving baseline yaw as the rover is
1095
significant lagged and gives no more information on position or
1096
velocity
1097
*/
1098
const bool using_moving_base = is_rtk_base(0) || is_rtk_base(1);
1099
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) {
1100
_output_is_blended = ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_weights();
1101
} else {
1102
_output_is_blended = false;
1103
((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->zero_health_counter();
1104
}
1105
1106
if (_output_is_blended) {
1107
// Use the weighting to calculate blended GPS states
1108
((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_state();
1109
// set primary to the virtual instance
1110
primary_instance = GPS_BLENDED_INSTANCE;
1111
return;
1112
}
1113
#endif // AP_GPS_BLENDED_ENABLED
1114
1115
// check the primary param is set to possible GPS
1116
int8_t primary_param = _primary.get();
1117
if ((primary_param < 0) || (primary_param>=GPS_MAX_RECEIVERS)) {
1118
primary_param = 0;
1119
}
1120
// if primary is not enabled try first instance
1121
if (get_type(primary_param) == GPS_TYPE_NONE) {
1122
primary_param = 0;
1123
}
1124
1125
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) {
1126
// No switching of GPSs, always use the primary instance
1127
primary_instance = primary_param;
1128
return;
1129
}
1130
1131
uint32_t now = AP_HAL::millis();
1132
1133
// special handling of RTK moving baseline pair. Always use the
1134
// base as the rover position is derived from the base, which
1135
// means the rover always has worse position and velocity than the
1136
// base. This overrides the normal logic which would select the
1137
// rover as it typically is in fix type 6 (RTK) whereas base is
1138
// usually fix type 3
1139
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1140
if (is_rtk_base(i) &&
1141
is_rtk_rover(i^1) &&
1142
((state[i].status >= GPS_OK_FIX_3D) || (state[i].status >= state[i^1].status))) {
1143
if (primary_instance != i) {
1144
_last_instance_swap_ms = now;
1145
primary_instance = i;
1146
}
1147
// don't do any more switching logic. We don't want the
1148
// RTK status of the rover to cause a switch
1149
return;
1150
}
1151
}
1152
1153
#if AP_GPS_BLENDED_ENABLED
1154
// handling switching away from blended GPS
1155
if (primary_instance == GPS_BLENDED_INSTANCE) {
1156
primary_instance = 0;
1157
for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {
1158
// choose GPS with highest state or higher number of
1159
// satellites. Reject a GPS with an old update time, as it
1160
// may be the old timestamp that triggered the loss of
1161
// blending
1162
const uint32_t delay_threshold = 400;
1163
const bool higher_status = state[i].status > state[primary_instance].status;
1164
const bool old_data_primary = (now - state[primary_instance].last_gps_time_ms) > delay_threshold;
1165
const bool old_data = (now - state[i].last_gps_time_ms) > delay_threshold;
1166
const bool equal_status = state[i].status == state[primary_instance].status;
1167
const bool more_sats = state[i].num_sats > state[primary_instance].num_sats;
1168
if (old_data && !old_data_primary) {
1169
// don't switch to a GPS that has not updated in 400ms
1170
continue;
1171
}
1172
if (state[i].status < GPS_OK_FIX_3D) {
1173
// don't use a GPS without 3D fix
1174
continue;
1175
}
1176
// select the new GPS if the primary has old data, or new
1177
// GPS either has higher status, or has the same status
1178
// and more satellites
1179
if ((old_data_primary && !old_data) ||
1180
higher_status ||
1181
(equal_status && more_sats)) {
1182
primary_instance = i;
1183
}
1184
}
1185
_last_instance_swap_ms = now;
1186
return;
1187
}
1188
#endif // AP_GPS_BLENDED_ENABLED
1189
1190
// Use primary if 3D fix or better
1191
if (((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_PRIMARY_IF_3D_FIX) && (state[primary_param].status >= GPS_OK_FIX_3D)) {
1192
// Primary GPS has a least a 3D fix, switch to it if necessary
1193
if (primary_instance != primary_param) {
1194
primary_instance = primary_param;
1195
_last_instance_swap_ms = now;
1196
}
1197
return;
1198
}
1199
1200
// handle switch between real GPSs
1201
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1202
if (i == primary_instance) {
1203
continue;
1204
}
1205
if (state[i].status > state[primary_instance].status) {
1206
// we have a higher status lock, or primary is set to the blended GPS, change GPS
1207
primary_instance = i;
1208
_last_instance_swap_ms = now;
1209
continue;
1210
}
1211
1212
bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
1213
1214
if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
1215
1216
bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
1217
1218
if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
1219
(another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
1220
// this GPS has more satellites than the
1221
// current primary, switch primary. Once we switch we will
1222
// then tend to stick to the new GPS as primary. We don't
1223
// want to switch too often as it will look like a
1224
// position shift to the controllers.
1225
primary_instance = i;
1226
_last_instance_swap_ms = now;
1227
}
1228
}
1229
}
1230
}
1231
#endif // GPS_MAX_RECEIVERS > 1
1232
1233
#if HAL_GCS_ENABLED
1234
void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
1235
{
1236
mavlink_gps_inject_data_t packet;
1237
mavlink_msg_gps_inject_data_decode(&msg, &packet);
1238
1239
if (packet.len > sizeof(packet.data)) {
1240
// invalid packet
1241
return;
1242
}
1243
1244
handle_gps_rtcm_fragment(0, packet.data, packet.len);
1245
}
1246
1247
/*
1248
pass along a mavlink message (for MAV type)
1249
*/
1250
void AP_GPS::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg)
1251
{
1252
switch (msg.msgid) {
1253
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
1254
// pass data to de-fragmenter
1255
handle_gps_rtcm_data(chan, msg);
1256
break;
1257
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
1258
handle_gps_inject(msg);
1259
break;
1260
default: {
1261
uint8_t i;
1262
for (i=0; i<num_instances; i++) {
1263
if ((drivers[i] != nullptr) && (params[i].type != GPS_TYPE_NONE)) {
1264
drivers[i]->handle_msg(msg);
1265
}
1266
}
1267
break;
1268
}
1269
}
1270
}
1271
#endif
1272
1273
#if HAL_MSP_GPS_ENABLED
1274
void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt)
1275
{
1276
for (uint8_t i=0; i<num_instances; i++) {
1277
if (drivers[i] != nullptr && params[i].type == GPS_TYPE_MSP) {
1278
drivers[i]->handle_msp(pkt);
1279
}
1280
}
1281
}
1282
#endif // HAL_MSP_GPS_ENABLED
1283
1284
#if HAL_EXTERNAL_AHRS_ENABLED
1285
1286
bool AP_GPS::get_first_external_instance(uint8_t& instance) const
1287
{
1288
for (uint8_t i=0; i<num_instances; i++) {
1289
if (drivers[i] != nullptr && params[i].type == GPS_TYPE_EXTERNAL_AHRS) {
1290
instance = i;
1291
return true;
1292
}
1293
}
1294
return false;
1295
}
1296
1297
void AP_GPS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance)
1298
{
1299
if (get_type(instance) == GPS_TYPE_EXTERNAL_AHRS && drivers[instance] != nullptr) {
1300
drivers[instance]->handle_external(pkt);
1301
}
1302
}
1303
#endif // HAL_EXTERNAL_AHRS_ENABLED
1304
1305
/**
1306
Lock a GPS port, preventing the GPS driver from using it. This can
1307
be used to allow a user to control a GPS port via the
1308
SERIAL_CONTROL protocol
1309
*/
1310
void AP_GPS::lock_port(uint8_t instance, bool lock)
1311
{
1312
1313
if (instance >= GPS_MAX_RECEIVERS) {
1314
return;
1315
}
1316
if (lock) {
1317
locked_ports |= (1U<<instance);
1318
} else {
1319
locked_ports &= ~(1U<<instance);
1320
}
1321
}
1322
1323
// Inject a packet of raw binary to a GPS
1324
void AP_GPS::inject_data(const uint8_t *data, uint16_t len)
1325
{
1326
//Support broadcasting to all GPSes.
1327
if (_inject_to == GPS_RTK_INJECT_TO_ALL) {
1328
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1329
if (is_rtk_rover(i)) {
1330
// we don't externally inject to moving baseline rover
1331
continue;
1332
}
1333
inject_data(i, data, len);
1334
}
1335
} else {
1336
inject_data(_inject_to, data, len);
1337
}
1338
}
1339
1340
void AP_GPS::inject_data(uint8_t instance, const uint8_t *data, uint16_t len)
1341
{
1342
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
1343
drivers[instance]->inject_data(data, len);
1344
}
1345
}
1346
1347
/*
1348
get GPS yaw following mavlink GPS_RAW_INT and GPS2_RAW
1349
convention. We return 0 if the GPS is not configured to provide
1350
yaw. We return 65535 for a GPS configured to provide yaw that can't
1351
currently provide it. We return from 1 to 36000 for yaw otherwise
1352
*/
1353
uint16_t AP_GPS::gps_yaw_cdeg(uint8_t instance) const
1354
{
1355
if (!have_gps_yaw_configured(instance)) {
1356
return 0;
1357
}
1358
float yaw_deg, accuracy_deg;
1359
uint32_t time_ms;
1360
if (!gps_yaw_deg(instance, yaw_deg, accuracy_deg, time_ms)) {
1361
return 65535;
1362
}
1363
int yaw_cd = wrap_360_cd(yaw_deg * 100);
1364
if (yaw_cd == 0) {
1365
return 36000;
1366
}
1367
return yaw_cd;
1368
}
1369
1370
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
1371
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
1372
{
1373
const Location &loc = location(0);
1374
float hacc = 0.0f;
1375
float vacc = 0.0f;
1376
float sacc = 0.0f;
1377
float undulation = 0.0;
1378
int32_t height_elipsoid_mm = 0;
1379
if (get_undulation(0, undulation)) {
1380
height_elipsoid_mm = loc.alt*10 - undulation*1000;
1381
}
1382
horizontal_accuracy(0, hacc);
1383
vertical_accuracy(0, vacc);
1384
speed_accuracy(0, sacc);
1385
mavlink_msg_gps_raw_int_send(
1386
chan,
1387
last_fix_time_ms(0)*(uint64_t)1000,
1388
status(0),
1389
loc.lat, // in 1E7 degrees
1390
loc.lng, // in 1E7 degrees
1391
loc.alt * 10UL, // in mm
1392
get_hdop(0),
1393
get_vdop(0),
1394
ground_speed(0)*100, // cm/s
1395
ground_course(0)*100, // 1/100 degrees,
1396
num_sats(0),
1397
height_elipsoid_mm, // Ellipsoid height in mm
1398
hacc * 1000, // one-sigma standard deviation in mm
1399
vacc * 1000, // one-sigma standard deviation in mm
1400
sacc * 1000, // one-sigma standard deviation in mm/s
1401
0, // TODO one-sigma heading accuracy standard deviation
1402
gps_yaw_cdeg(0));
1403
}
1404
#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED
1405
1406
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
1407
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
1408
{
1409
// always send the message if 2nd GPS is configured
1410
if (params[1].type == GPS_TYPE_NONE) {
1411
return;
1412
}
1413
1414
const Location &loc = location(1);
1415
float hacc = 0.0f;
1416
float vacc = 0.0f;
1417
float sacc = 0.0f;
1418
float undulation = 0.0;
1419
float height_elipsoid_mm = 0;
1420
if (get_undulation(1, undulation)) {
1421
height_elipsoid_mm = loc.alt*10 - undulation*1000;
1422
}
1423
horizontal_accuracy(1, hacc);
1424
vertical_accuracy(1, vacc);
1425
speed_accuracy(1, sacc);
1426
mavlink_msg_gps2_raw_send(
1427
chan,
1428
last_fix_time_ms(1)*(uint64_t)1000,
1429
status(1),
1430
loc.lat,
1431
loc.lng,
1432
loc.alt * 10UL,
1433
get_hdop(1),
1434
get_vdop(1),
1435
ground_speed(1)*100, // cm/s
1436
ground_course(1)*100, // 1/100 degrees,
1437
num_sats(1),
1438
state[1].rtk_num_sats,
1439
state[1].rtk_age_ms,
1440
gps_yaw_cdeg(1),
1441
height_elipsoid_mm, // Ellipsoid height in mm
1442
hacc * 1000, // one-sigma standard deviation in mm
1443
vacc * 1000, // one-sigma standard deviation in mm
1444
sacc * 1000, // one-sigma standard deviation in mm/s
1445
0); // TODO one-sigma heading accuracy standard deviation
1446
}
1447
#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED
1448
1449
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
1450
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
1451
{
1452
if (inst >= GPS_MAX_RECEIVERS) {
1453
return;
1454
}
1455
if (drivers[inst] != nullptr && drivers[inst]->supports_mavlink_gps_rtk_message()) {
1456
drivers[inst]->send_mavlink_gps_rtk(chan);
1457
}
1458
}
1459
#endif
1460
1461
bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const
1462
{
1463
for (int i = 0; i < GPS_MAX_RECEIVERS; i++) {
1464
if (params[i].type != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {
1465
instance = i;
1466
return true;
1467
}
1468
}
1469
return false;
1470
}
1471
1472
void AP_GPS::broadcast_first_configuration_failure_reason(void) const
1473
{
1474
uint8_t unconfigured;
1475
if (first_unconfigured_gps(unconfigured)) {
1476
if (drivers[unconfigured] == nullptr) {
1477
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
1478
} else {
1479
drivers[unconfigured]->broadcast_configuration_failure_reason();
1480
}
1481
}
1482
}
1483
1484
// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
1485
bool AP_GPS::all_consistent(float &distance) const
1486
{
1487
// return true immediately if only one valid receiver
1488
if (num_instances <= 1 ||
1489
drivers[0] == nullptr || params[0].type == GPS_TYPE_NONE) {
1490
distance = 0;
1491
return true;
1492
}
1493
1494
// calculate distance
1495
distance = state[0].location.get_distance_NED(state[1].location).length();
1496
// success if distance is within 50m
1497
return (distance < 50);
1498
}
1499
1500
/*
1501
re-assemble fragmented RTCM data
1502
*/
1503
void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len)
1504
{
1505
if ((flags & 1) == 0) {
1506
// it is not fragmented, pass direct
1507
inject_data(data, len);
1508
return;
1509
}
1510
1511
// see if we need to allocate re-assembly buffer
1512
if (rtcm_buffer == nullptr) {
1513
rtcm_buffer = (struct rtcm_buffer *)calloc(1, sizeof(*rtcm_buffer));
1514
if (rtcm_buffer == nullptr) {
1515
// nothing to do but discard the data
1516
return;
1517
}
1518
}
1519
1520
const uint8_t fragment = (flags >> 1U) & 0x03;
1521
const uint8_t sequence = (flags >> 3U) & 0x1F;
1522
uint8_t* start_of_fragment_in_buffer = &rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN * (uint16_t)fragment];
1523
bool should_clear_previous_fragments = false;
1524
1525
if (rtcm_buffer->fragments_received) {
1526
const bool sequence_nr_changed = rtcm_buffer->sequence != sequence;
1527
const bool seen_this_fragment_index = rtcm_buffer->fragments_received & (1U << fragment);
1528
1529
// check whether this is a duplicate fragment. If it is, we can
1530
// return early.
1531
if (!sequence_nr_changed && seen_this_fragment_index && !memcmp(start_of_fragment_in_buffer, data, len)) {
1532
return;
1533
}
1534
1535
// not a duplicate
1536
should_clear_previous_fragments = sequence_nr_changed || seen_this_fragment_index;
1537
}
1538
1539
if (should_clear_previous_fragments) {
1540
// we have one or more partial fragments already received
1541
// which conflict with the new fragment, discard previous fragments
1542
rtcm_buffer->fragment_count = 0;
1543
rtcm_stats.fragments_discarded += __builtin_popcount(rtcm_buffer->fragments_received);
1544
rtcm_buffer->fragments_received = 0;
1545
}
1546
1547
// add this fragment
1548
rtcm_buffer->sequence = sequence;
1549
rtcm_buffer->fragments_received |= (1U << fragment);
1550
1551
// copy the data
1552
memcpy(start_of_fragment_in_buffer, data, len);
1553
1554
// when we get a fragment of less than max size then we know the
1555
// number of fragments. Note that this means if you want to send a
1556
// block of RTCM data of an exact multiple of the buffer size you
1557
// need to send a final packet of zero length
1558
if (len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1559
rtcm_buffer->fragment_count = fragment+1;
1560
rtcm_buffer->total_length = (MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*fragment) + len;
1561
} else if (rtcm_buffer->fragments_received == 0x0F) {
1562
// special case of 4 full fragments
1563
rtcm_buffer->fragment_count = 4;
1564
rtcm_buffer->total_length = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4;
1565
}
1566
1567
1568
// see if we have all fragments
1569
if (rtcm_buffer->fragment_count != 0 &&
1570
rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
1571
// we have them all, inject
1572
rtcm_stats.fragments_used += __builtin_popcount(rtcm_buffer->fragments_received);
1573
inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);
1574
rtcm_buffer->fragment_count = 0;
1575
rtcm_buffer->fragments_received = 0;
1576
}
1577
}
1578
1579
/*
1580
re-assemble GPS_RTCM_DATA message
1581
*/
1582
void AP_GPS::handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_t &msg)
1583
{
1584
mavlink_gps_rtcm_data_t packet;
1585
mavlink_msg_gps_rtcm_data_decode(&msg, &packet);
1586
1587
if (packet.len > sizeof(packet.data)) {
1588
// invalid packet
1589
return;
1590
}
1591
1592
#if AP_GPS_RTCM_DECODE_ENABLED
1593
if (!option_set(DriverOptions::DisableRTCMDecode)) {
1594
const uint16_t mask = (1U << unsigned(chan));
1595
rtcm.seen_mav_channels |= mask;
1596
if (option_set(DriverOptions::AlwaysRTCMDecode) ||
1597
(rtcm.seen_mav_channels & ~mask) != 0) {
1598
/*
1599
we are seeing RTCM on multiple mavlink channels. We will run
1600
the data through a full per-channel RTCM decoder
1601
*/
1602
if (parse_rtcm_injection(chan, packet)) {
1603
return;
1604
}
1605
}
1606
}
1607
#endif
1608
1609
handle_gps_rtcm_fragment(packet.flags, packet.data, packet.len);
1610
}
1611
1612
#if AP_GPS_RTCM_DECODE_ENABLED
1613
/*
1614
fully parse RTCM data coming in from a MAVLink channel, when we have
1615
a full message inject it to the GPS. This approach allows for 2 or
1616
more MAVLink channels to be used for the same RTCM data, allowing
1617
for redundent transports for maximum reliability at the cost of some
1618
extra CPU and a bit of re-assembly lag
1619
*/
1620
bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt)
1621
{
1622
if (static_cast<int>(chan) >= MAVLINK_COMM_NUM_BUFFERS) {
1623
return false;
1624
}
1625
if (rtcm.parsers[chan] == nullptr) {
1626
rtcm.parsers[chan] = NEW_NOTHROW RTCM3_Parser();
1627
if (rtcm.parsers[chan] == nullptr) {
1628
return false;
1629
}
1630
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS: RTCM parsing for chan %u", unsigned(chan));
1631
}
1632
for (uint16_t i=0; i<pkt.len; i++) {
1633
if (rtcm.parsers[chan]->read(pkt.data[i])) {
1634
// we have a full message, inject it
1635
const uint8_t *buf = nullptr;
1636
uint16_t len = rtcm.parsers[chan]->get_len(buf);
1637
1638
// see if we have already sent it. This prevents
1639
// duplicates from multiple sources
1640
const uint32_t crc = crc_crc32(0, buf, len);
1641
1642
#if HAL_LOGGING_ENABLED
1643
AP::logger().WriteStreaming("RTCM", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI",
1644
AP_HAL::micros64(),
1645
uint8_t(chan),
1646
rtcm.parsers[chan]->get_id(),
1647
len,
1648
crc);
1649
#endif
1650
1651
bool already_seen = false;
1652
for (uint8_t c=0; c<ARRAY_SIZE(rtcm.sent_crc); c++) {
1653
if (rtcm.sent_crc[c] == crc) {
1654
// we have already sent this message
1655
already_seen = true;
1656
break;
1657
}
1658
}
1659
if (already_seen) {
1660
continue;
1661
}
1662
rtcm.sent_crc[rtcm.sent_idx] = crc;
1663
rtcm.sent_idx = (rtcm.sent_idx+1) % ARRAY_SIZE(rtcm.sent_crc);
1664
1665
if (buf != nullptr && len > 0) {
1666
inject_data(buf, len);
1667
}
1668
rtcm.parsers[chan]->reset();
1669
}
1670
}
1671
return true;
1672
}
1673
#endif // AP_GPS_RTCM_DECODE_ENABLED
1674
1675
#if HAL_LOGGING_ENABLED
1676
void AP_GPS::Write_AP_Logger_Log_Startup_messages()
1677
{
1678
for (uint8_t instance=0; instance<num_instances; instance++) {
1679
if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1680
continue;
1681
}
1682
drivers[instance]->Write_AP_Logger_Log_Startup_messages();
1683
}
1684
}
1685
#endif
1686
1687
/*
1688
return the expected lag (in seconds) in the position and velocity readings from the gps
1689
return true if the GPS hardware configuration is known or the delay parameter has been set
1690
*/
1691
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
1692
{
1693
// always ensure a lag is provided
1694
lag_sec = 0.1f;
1695
1696
if (instance >= GPS_MAX_INSTANCES) {
1697
return false;
1698
}
1699
1700
#if AP_GPS_BLENDED_ENABLED
1701
// return lag of blended GPS
1702
if (instance == GPS_BLENDED_INSTANCE) {
1703
return drivers[instance]->get_lag(lag_sec);
1704
}
1705
#endif
1706
1707
if (params[instance].delay_ms > 0) {
1708
// if the user has specified a non zero time delay, always return that value
1709
lag_sec = 0.001f * (float)params[instance].delay_ms;
1710
// the user is always right !!
1711
return true;
1712
} else if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1713
// no GPS was detected in this instance so return the worst possible lag term
1714
const auto type = params[instance].type;
1715
if (type == GPS_TYPE_NONE) {
1716
lag_sec = 0.0f;
1717
return true;
1718
}
1719
return type == GPS_TYPE_AUTO;
1720
} else {
1721
// the user has not specified a delay so we determine it from the GPS type
1722
return drivers[instance]->get_lag(lag_sec);
1723
}
1724
}
1725
1726
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
1727
const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
1728
{
1729
if (instance >= GPS_MAX_INSTANCES) {
1730
// we have to return a reference so use instance 0
1731
return params[0].antenna_offset;
1732
}
1733
1734
#if AP_GPS_BLENDED_ENABLED
1735
if (instance == GPS_BLENDED_INSTANCE) {
1736
// return an offset for the blended GPS solution
1737
return ((AP_GPS_Blended*)drivers[instance])->get_antenna_offset();
1738
}
1739
#endif
1740
1741
return params[instance].antenna_offset;
1742
}
1743
1744
/*
1745
returns the desired gps update rate in milliseconds
1746
this does not provide any guarantee that the GPS is updating at the requested
1747
rate it is simply a helper for use in the backends for determining what rate
1748
they should be configuring the GPS to run at
1749
*/
1750
uint16_t AP_GPS::get_rate_ms(uint8_t instance) const
1751
{
1752
// sanity check
1753
if (instance >= num_instances || params[instance].rate_ms <= 0) {
1754
return GPS_MAX_RATE_MS;
1755
}
1756
return MIN(params[instance].rate_ms, GPS_MAX_RATE_MS);
1757
}
1758
1759
bool AP_GPS::is_healthy(uint8_t instance) const
1760
{
1761
if (instance >= GPS_MAX_INSTANCES) {
1762
return false;
1763
}
1764
1765
if (get_type(_primary.get()) == GPS_TYPE_NONE) {
1766
return false;
1767
}
1768
1769
#ifndef HAL_BUILD_AP_PERIPH
1770
/*
1771
on AP_Periph handling of timing is done by the flight controller
1772
receiving the DroneCAN messages
1773
*/
1774
/*
1775
allow two lost frames before declaring the GPS unhealthy, but
1776
require the average frame rate to be close to 5Hz.
1777
1778
We allow for a rate of 3Hz average for a moving baseline rover
1779
due to the packet loss that happens with the RTCMv3 data and the
1780
fact that the rate of yaw data is not critical
1781
*/
1782
const uint8_t delay_threshold = 2;
1783
const float delay_avg_max = is_rtk_rover(instance) ? 333 : 215;
1784
const GPS_timing &t = timing[instance];
1785
bool delay_ok = (t.delayed_count < delay_threshold) &&
1786
t.average_delta_ms < delay_avg_max &&
1787
state[instance].lagged_sample_count < 5;
1788
if (!delay_ok) {
1789
return false;
1790
}
1791
#endif // HAL_BUILD_AP_PERIPH
1792
1793
return drivers[instance] != nullptr &&
1794
drivers[instance]->is_healthy();
1795
}
1796
1797
bool AP_GPS::prepare_for_arming(void) {
1798
bool all_passed = true;
1799
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1800
if (drivers[i] != nullptr) {
1801
all_passed &= drivers[i]->prepare_for_arming();
1802
}
1803
}
1804
return all_passed;
1805
}
1806
1807
bool AP_GPS::pre_arm_checks(char failure_msg[], uint16_t failure_msg_len)
1808
{
1809
// the DroneCAN class has additional checks for DroneCAN-specific
1810
// parameters:
1811
#if AP_GPS_DRONECAN_ENABLED
1812
if (!AP_GPS_DroneCAN::inter_instance_pre_arm_checks(failure_msg, failure_msg_len)) {
1813
return false;
1814
}
1815
#endif
1816
1817
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1818
if (is_rtk_rover(i)) {
1819
if (AP_HAL::millis() - state[i].gps_yaw_time_ms > 15000) {
1820
hal.util->snprintf(failure_msg, failure_msg_len, "GPS[%u] yaw not available", unsigned(i+1));
1821
return false;
1822
}
1823
}
1824
}
1825
1826
#if AP_GPS_BLENDED_ENABLED
1827
if (!drivers[GPS_BLENDED_INSTANCE]->is_healthy()) {
1828
hal.util->snprintf(failure_msg, failure_msg_len, "GPS blending unhealthy");
1829
return false;
1830
}
1831
#endif
1832
1833
return true;
1834
}
1835
1836
bool AP_GPS::logging_failed(void) const {
1837
if (!logging_enabled()) {
1838
return false;
1839
}
1840
1841
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1842
if ((drivers[i] != nullptr) && !(drivers[i]->logging_healthy())) {
1843
return true;
1844
}
1845
}
1846
1847
return false;
1848
}
1849
1850
// get iTOW, if supported, zero otherwie
1851
uint32_t AP_GPS::get_itow(uint8_t instance) const
1852
{
1853
if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {
1854
return 0;
1855
}
1856
return drivers[instance]->get_last_itow_ms();
1857
}
1858
1859
bool AP_GPS::get_error_codes(uint8_t instance, uint32_t &error_codes) const
1860
{
1861
if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {
1862
return false;
1863
}
1864
1865
return drivers[instance]->get_error_codes(error_codes);
1866
}
1867
1868
// get the difference between WGS84 and AMSL. A positive value means
1869
// the AMSL height is higher than WGS84 ellipsoid height
1870
bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const
1871
{
1872
if (!state[instance].have_undulation) {
1873
return false;
1874
}
1875
undulation = state[instance].undulation;
1876
return true;
1877
}
1878
1879
#if HAL_LOGGING_ENABLED
1880
// Logging support:
1881
// Write an GPS packet
1882
void AP_GPS::Write_GPS(uint8_t i)
1883
{
1884
const uint64_t time_us = AP_HAL::micros64();
1885
const Location &loc = location(i);
1886
1887
float yaw_deg=0, yaw_accuracy_deg=0;
1888
uint32_t yaw_time_ms;
1889
gps_yaw_deg(i, yaw_deg, yaw_accuracy_deg, yaw_time_ms);
1890
1891
const struct log_GPS pkt {
1892
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
1893
time_us : time_us,
1894
instance : i,
1895
status : (uint8_t)status(i),
1896
gps_week_ms : time_week_ms(i),
1897
gps_week : time_week(i),
1898
num_sats : num_sats(i),
1899
hdop : get_hdop(i),
1900
latitude : loc.lat,
1901
longitude : loc.lng,
1902
altitude : loc.alt,
1903
ground_speed : ground_speed(i),
1904
ground_course : ground_course(i),
1905
vel_z : velocity(i).z,
1906
yaw : yaw_deg,
1907
used : (uint8_t)(AP::gps().primary_sensor() == i)
1908
};
1909
AP::logger().WriteBlock(&pkt, sizeof(pkt));
1910
1911
/* write auxiliary accuracy information as well */
1912
float hacc = 0, vacc = 0, sacc = 0;
1913
float undulation = 0;
1914
horizontal_accuracy(i, hacc);
1915
vertical_accuracy(i, vacc);
1916
speed_accuracy(i, sacc);
1917
get_undulation(i, undulation);
1918
struct log_GPA pkt2{
1919
LOG_PACKET_HEADER_INIT(LOG_GPA_MSG),
1920
time_us : time_us,
1921
instance : i,
1922
vdop : get_vdop(i),
1923
hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),
1924
vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
1925
sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
1926
yaw_accuracy : yaw_accuracy_deg,
1927
have_vv : (uint8_t)have_vertical_velocity(i),
1928
sample_ms : last_message_time_ms(i),
1929
delta_ms : last_message_delta_time_ms(i),
1930
undulation : undulation,
1931
rtcm_fragments_used: rtcm_stats.fragments_used,
1932
rtcm_fragments_discarded: rtcm_stats.fragments_discarded
1933
};
1934
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
1935
}
1936
#endif
1937
1938
bool AP_GPS::is_rtk_base(uint8_t instance) const
1939
{
1940
switch (get_type(instance)) {
1941
case GPS_TYPE_UBLOX_RTK_BASE:
1942
case GPS_TYPE_UAVCAN_RTK_BASE:
1943
return true;
1944
default:
1945
break;
1946
}
1947
return false;
1948
}
1949
1950
bool AP_GPS::is_rtk_rover(uint8_t instance) const
1951
{
1952
switch (get_type(instance)) {
1953
case GPS_TYPE_UBLOX_RTK_ROVER:
1954
case GPS_TYPE_UAVCAN_RTK_ROVER:
1955
return true;
1956
default:
1957
break;
1958
}
1959
return false;
1960
}
1961
1962
/*
1963
get GPS based yaw
1964
*/
1965
bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const
1966
{
1967
#if GPS_MAX_RECEIVERS > 1
1968
if (is_rtk_base(instance) && is_rtk_rover(instance^1)) {
1969
// return the yaw from the rover
1970
instance ^= 1;
1971
}
1972
#endif
1973
if (!have_gps_yaw(instance)) {
1974
return false;
1975
}
1976
yaw_deg = state[instance].gps_yaw;
1977
1978
// get lagged timestamp
1979
time_ms = state[instance].gps_yaw_time_ms;
1980
float lag_s;
1981
if (get_lag(instance, lag_s)) {
1982
uint32_t lag_ms = lag_s * 1000;
1983
time_ms -= lag_ms;
1984
}
1985
1986
if (state[instance].have_gps_yaw_accuracy) {
1987
accuracy_deg = state[instance].gps_yaw_accuracy;
1988
} else {
1989
// fall back to 10 degrees as a generic default
1990
accuracy_deg = 10;
1991
}
1992
return true;
1993
}
1994
1995
/*
1996
* Old parameter metadata. Until we have versioned parameters, keeping
1997
* old parameters around for a while can help with an adjustment
1998
* period.
1999
*/
2000
2001
// @Param: _TYPE
2002
// @DisplayName: 1st GPS type
2003
// @Description: GPS type of 1st GPS.Renamed in 4.6 and later to GPS1_TYPE
2004
// @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna
2005
// @RebootRequired: True
2006
// @User: Advanced
2007
// @Legacy: only included here so GCSs running stable can get the description. Omitted in the Wiki.
2008
2009
// @Param: _TYPE2
2010
// @CopyFieldsFrom: GPS_TYPE
2011
// @DisplayName: 2nd GPS type.Renamed in 4.6 to GPS2_TYPE
2012
// @Description: GPS type of 2nd GPS
2013
// @Legacy: 4.5 param
2014
2015
// @Param: _GNSS_MODE
2016
// @DisplayName: GNSS system configuration
2017
// @Description: Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured).Renamed in 4.6 and later to GPS1_GNSS_MODE.
2018
// @Legacy: 4.5 param
2019
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
2020
// @User: Advanced
2021
2022
// @Param: _GNSS_MODE2
2023
// @DisplayName: GNSS system configuration.
2024
// @Description: Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured). Renamed in 4.6 and later to GPS2_GNSS_MODE
2025
// @Legacy: 4.5 param
2026
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
2027
// @User: Advanced
2028
2029
// @Param: _RATE_MS
2030
// @DisplayName: GPS update rate in milliseconds
2031
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS1_RATE_MS
2032
// @Legacy: 4.5 param
2033
// @Units: ms
2034
// @Values: 100:10Hz,125:8Hz,200:5Hz
2035
// @Range: 50 200
2036
// @User: Advanced
2037
2038
// @Param: _RATE_MS2
2039
// @DisplayName: GPS 2 update rate in milliseconds
2040
// @Description: Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.Renamed in 4.6 and later to GPS2_RATE_MS
2041
// @Legacy: 4.5 param
2042
// @Units: ms
2043
// @Values: 100:10Hz,125:8Hz,200:5Hz
2044
// @Range: 50 200
2045
// @User: Advanced
2046
2047
// @Param: _POS1_X
2048
// @DisplayName: Antenna X position offset
2049
// @Description: X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_X.
2050
// @Legacy: 4.5 param
2051
// @Units: m
2052
// @Range: -5 5
2053
// @Increment: 0.01
2054
// @User: Advanced
2055
2056
// @Param: _POS1_Y
2057
// @DisplayName: Antenna Y position offset
2058
// @Description: Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_Y.
2059
// @Legacy: 4.5 param
2060
// @Units: m
2061
// @Range: -5 5
2062
// @Increment: 0.01
2063
// @User: Advanced
2064
2065
// @Param: _POS1_Z
2066
// @DisplayName: Antenna Z position offset
2067
// @Description: Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS1_POS_Z.
2068
// @Legacy: 4.5 param
2069
// @Units: m
2070
// @Range: -5 5
2071
// @Increment: 0.01
2072
// @User: Advanced
2073
2074
// @Param: _POS2_X
2075
// @DisplayName: Antenna X position offset
2076
// @Description: X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_X.
2077
// @Legacy: 4.5 param
2078
// @Units: m
2079
// @Range: -5 5
2080
// @Increment: 0.01
2081
// @User: Advanced
2082
2083
// @Param: _POS2_Y
2084
// @DisplayName: Antenna Y position offset
2085
// @Description: Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_Y.
2086
// @Legacy: 4.5 param
2087
// @Units: m
2088
// @Range: -5 5
2089
// @Increment: 0.01
2090
// @User: Advanced
2091
2092
// @Param: _POS2_Z
2093
// @DisplayName: Antenna Z position offset
2094
// @Description: Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.Renamed in 4.6 and later to GPS2_POS_Z.
2095
// @Legacy: 4.5 param
2096
// @Units: m
2097
// @Range: -5 5
2098
// @Increment: 0.01
2099
// @User: Advanced
2100
2101
// @Param: _DELAY_MS
2102
// @DisplayName: GPS delay in milliseconds
2103
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS1_DELAY_MS.
2104
// @Legacy: 4.5 param
2105
// @Units: ms
2106
// @Range: 0 250
2107
// @User: Advanced
2108
// @RebootRequired: True
2109
2110
// @Param: _DELAY_MS2
2111
// @DisplayName: GPS 2 delay in milliseconds
2112
// @Description: Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.Renamed in 4.6 and later to GPS2_DELAY_MS.
2113
// @Legacy: 4.5 param
2114
// @Units: ms
2115
// @Range: 0 250
2116
// @User: Advanced
2117
// @RebootRequired: True
2118
2119
// @Param: _COM_PORT
2120
// @DisplayName: GPS physical COM port
2121
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS,Renamed in 4.6 and later to GPS1_COM_PORT.
2122
// @Legacy: 4.5 param
2123
// @Range: 0 10
2124
// @Increment: 1
2125
// @User: Advanced
2126
// @Values: 0:COM1(RS232) on GSOF, 1:COM2(TTL) on GSOF
2127
// @RebootRequired: True
2128
2129
// @Param: _COM_PORT2
2130
// @DisplayName: GPS physical COM port
2131
// @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS.Renamed in 4.6 and later to GPS1_COM_PORT.
2132
// @Legacy: 4.5 param
2133
// @Range: 0 10
2134
// @Increment: 1
2135
// @User: Advanced
2136
// @RebootRequired: True
2137
2138
// @Group: _MB1_
2139
// @Path: MovingBase.cpp
2140
// @Legacy: 4.5 param
2141
2142
// @Group: _MB2_
2143
// @Path: MovingBase.cpp
2144
// @Legacy: 4.5 param
2145
2146
// @Param: _CAN_NODEID1
2147
// @DisplayName: GPS Node ID 1
2148
// @Description: GPS Node id for first-discovered GPS.Renamed in 4.6 and later to GPS1_CAN_NODEID.
2149
// @Legacy: 4.5 param
2150
// @ReadOnly: True
2151
// @User: Advanced
2152
2153
// @Param: _CAN_NODEID2
2154
// @DisplayName: GPS Node ID 2
2155
// @Description: GPS Node id for second-discovered GPS.Renamed in 4.6 and later to GPS2_CAN_NODEID.
2156
// @Legacy: 4.5 param
2157
// @ReadOnly: True
2158
// @User: Advanced
2159
2160
/*
2161
* end old parameter metadata
2162
*/
2163
2164
namespace AP {
2165
2166
AP_GPS &gps()
2167
{
2168
return *AP_GPS::get_singleton();
2169
}
2170
2171
};
2172
2173
#endif // AP_GPS_ENABLED
2174
2175