Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS.cpp
9383 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
#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 AP_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 on ublox,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<ARRAY_SIZE(_port); 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 AP_SIM_GPS_ENABLED
565
case GPS_TYPE_SITL:
566
#endif // AP_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 (instance >= ARRAY_SIZE(_port) ||
589
_port[instance] == nullptr) {
590
return;
591
}
592
593
if (initblob_state[instance].remaining == 0) {
594
return;
595
}
596
597
// see if we can write some more of the initialisation blob
598
const uint16_t n = MIN(_port[instance]->txspace(),
599
initblob_state[instance].remaining);
600
const size_t written = _port[instance]->write((const uint8_t*)initblob_state[instance].blob, n);
601
initblob_state[instance].blob += written;
602
initblob_state[instance].remaining -= written;
603
}
604
605
/*
606
run detection step for one GPS instance. If this finds a GPS then it
607
will fill in drivers[instance] and change state[instance].status
608
from NO_GPS to NO_FIX.
609
*/
610
void AP_GPS::detect_instance(uint8_t instance)
611
{
612
const uint32_t now = AP_HAL::millis();
613
614
state[instance].status = NO_GPS;
615
state[instance].hdop = GPS_UNKNOWN_DOP;
616
state[instance].vdop = GPS_UNKNOWN_DOP;
617
618
AP_GPS_Backend *new_gps = _detect_instance(instance);
619
if (new_gps == nullptr) {
620
return;
621
}
622
623
state[instance].status = NO_FIX;
624
drivers[instance] = new_gps;
625
timing[instance].last_message_time_ms = now;
626
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
627
628
new_gps->broadcast_gps_type();
629
}
630
631
/*
632
run detection step for one GPS instance. If this finds a GPS then it
633
will return it - otherwise nullptr
634
*/
635
AP_GPS_Backend *AP_GPS::_detect_instance(const uint8_t instance)
636
{
637
struct detect_state *dstate = &detect_state[instance];
638
639
const auto type = params[instance].type;
640
auto *port = (instance < ARRAY_SIZE(_port)) ? _port[instance] : nullptr;
641
642
switch (GPS_Type(type)) {
643
// user has to explicitly set the MAV type, do not use AUTO
644
// do not try to detect the MAV type, assume it's there
645
case GPS_TYPE_MAV:
646
#if AP_GPS_MAV_ENABLED
647
dstate->auto_detected_baud = false; // specified, not detected
648
return NEW_NOTHROW AP_GPS_MAV(*this, params[instance], state[instance], nullptr);
649
#endif //AP_GPS_MAV_ENABLED
650
651
// user has to explicitly set the UAVCAN type, do not use AUTO
652
case GPS_TYPE_UAVCAN:
653
case GPS_TYPE_UAVCAN_RTK_BASE:
654
case GPS_TYPE_UAVCAN_RTK_ROVER:
655
#if AP_GPS_DRONECAN_ENABLED
656
dstate->auto_detected_baud = false; // specified, not detected
657
return AP_GPS_DroneCAN::probe(*this, state[instance]);
658
#endif
659
return nullptr; // We don't do anything here if UAVCAN is not supported
660
#if HAL_MSP_GPS_ENABLED
661
case GPS_TYPE_MSP:
662
dstate->auto_detected_baud = false; // specified, not detected
663
return NEW_NOTHROW AP_GPS_MSP(*this, params[instance], state[instance], nullptr);
664
#endif
665
#if AP_EXTERNAL_AHRS_ENABLED
666
case GPS_TYPE_EXTERNAL_AHRS:
667
if (AP::externalAHRS().get_port(AP_ExternalAHRS::AvailableSensor::GPS) >= 0) {
668
dstate->auto_detected_baud = false; // specified, not detected
669
return NEW_NOTHROW AP_GPS_ExternalAHRS(*this, params[instance], state[instance], nullptr);
670
}
671
break;
672
#endif
673
#if AP_GPS_GSOF_ENABLED
674
case GPS_TYPE_GSOF:
675
dstate->auto_detected_baud = false; // specified, not detected
676
return NEW_NOTHROW AP_GPS_GSOF(*this, params[instance], state[instance], port);
677
#endif //AP_GPS_GSOF_ENABLED
678
default:
679
break;
680
}
681
682
if (port == nullptr) {
683
// UART not available
684
return nullptr;
685
}
686
687
// all remaining drivers automatically cycle through baud rates to detect
688
// the correct baud rate, and should have the selected baud broadcast
689
dstate->auto_detected_baud = true;
690
const uint32_t now = AP_HAL::millis();
691
692
if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
693
// try the next baud rate
694
// incrementing like this will skip the first element in array of bauds
695
// this is okay, and relied upon
696
if (dstate->probe_baud == 0) {
697
dstate->probe_baud = port->get_baud_rate();
698
} else {
699
dstate->current_baud++;
700
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
701
dstate->current_baud = 0;
702
}
703
dstate->probe_baud = _baudrates[dstate->current_baud];
704
}
705
uint16_t rx_size=0, tx_size=0;
706
if (type == GPS_TYPE_UBLOX_RTK_ROVER) {
707
tx_size = 2048;
708
}
709
if (type == GPS_TYPE_UBLOX_RTK_BASE) {
710
rx_size = 2048;
711
}
712
port->begin(dstate->probe_baud, rx_size, tx_size);
713
port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
714
dstate->last_baud_change_ms = now;
715
716
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
717
send_blob_start(instance);
718
}
719
}
720
721
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
722
send_blob_update(instance);
723
}
724
725
switch (GPS_Type(type)) {
726
#if AP_GPS_SBF_ENABLED
727
// by default the sbf/trimble gps outputs no data on its port, until configured.
728
case GPS_TYPE_SBF:
729
case GPS_TYPE_SBF_DUAL_ANTENNA:
730
return NEW_NOTHROW AP_GPS_SBF(*this, params[instance], state[instance], port);
731
#endif //AP_GPS_SBF_ENABLED
732
#if AP_GPS_NOVA_ENABLED
733
case GPS_TYPE_NOVA:
734
return NEW_NOTHROW AP_GPS_NOVA(*this, params[instance], state[instance], port);
735
#endif //AP_GPS_NOVA_ENABLED
736
737
#if AP_SIM_GPS_ENABLED
738
case GPS_TYPE_SITL:
739
return NEW_NOTHROW AP_GPS_SITL(*this, params[instance], state[instance], port);
740
#endif // AP_SIM_GPS_ENABLED
741
742
default:
743
break;
744
}
745
746
if (initblob_state[instance].remaining != 0) {
747
// don't run detection engines if we haven't sent out the initblobs
748
return nullptr;
749
}
750
751
uint16_t bytecount = MIN(8192U, port->available());
752
753
while (bytecount-- > 0) {
754
const uint8_t data = port->read();
755
(void)data; // if all backends are compiled out then "data" is unused
756
757
#if AP_GPS_UBLOX_ENABLED
758
if ((type == GPS_TYPE_AUTO ||
759
type == GPS_TYPE_UBLOX) &&
760
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
761
(_baudrates[dstate->current_baud] >= 115200 && option_set(DriverOptions::UBX_Use115200)) ||
762
_baudrates[dstate->current_baud] == 230400) &&
763
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
764
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], port, GPS_ROLE_NORMAL);
765
}
766
767
const uint32_t ublox_mb_required_baud = option_set(DriverOptions::UBX_MBUseUart2)?230400:460800;
768
if ((type == GPS_TYPE_UBLOX_RTK_BASE ||
769
type == GPS_TYPE_UBLOX_RTK_ROVER) &&
770
_baudrates[dstate->current_baud] == ublox_mb_required_baud &&
771
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
772
GPS_Role role;
773
if (type == GPS_TYPE_UBLOX_RTK_BASE) {
774
role = GPS_ROLE_MB_BASE;
775
} else {
776
role = GPS_ROLE_MB_ROVER;
777
}
778
return NEW_NOTHROW AP_GPS_UBLOX(*this, params[instance], state[instance], port, role);
779
}
780
#endif // AP_GPS_UBLOX_ENABLED
781
#if AP_GPS_SBP2_ENABLED
782
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
783
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {
784
return NEW_NOTHROW AP_GPS_SBP2(*this, params[instance], state[instance], port);
785
}
786
#endif //AP_GPS_SBP2_ENABLED
787
#if AP_GPS_SBP_ENABLED
788
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SBP) &&
789
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
790
return NEW_NOTHROW AP_GPS_SBP(*this, params[instance], state[instance], port);
791
}
792
#endif //AP_GPS_SBP_ENABLED
793
#if AP_GPS_SIRF_ENABLED
794
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_SIRF) &&
795
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
796
return NEW_NOTHROW AP_GPS_SIRF(*this, params[instance], state[instance], port);
797
}
798
#endif
799
#if AP_GPS_ERB_ENABLED
800
if ((type == GPS_TYPE_AUTO || type == GPS_TYPE_ERB) &&
801
AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
802
return NEW_NOTHROW AP_GPS_ERB(*this, params[instance], state[instance], port);
803
}
804
#endif // AP_GPS_ERB_ENABLED
805
#if AP_GPS_NMEA_ENABLED
806
if ((type == GPS_TYPE_NMEA ||
807
type == GPS_TYPE_HEMI ||
808
#if AP_GPS_NMEA_UNICORE_ENABLED
809
type == GPS_TYPE_UNICORE_NMEA ||
810
type == GPS_TYPE_UNICORE_MOVINGBASE_NMEA ||
811
#endif
812
type == GPS_TYPE_ALLYSTAR) &&
813
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
814
return NEW_NOTHROW AP_GPS_NMEA(*this, params[instance], state[instance], port);
815
}
816
#endif //AP_GPS_NMEA_ENABLED
817
}
818
819
return nullptr;
820
}
821
822
AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
823
{
824
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
825
return drivers[instance]->highest_supported_status();
826
}
827
return AP_GPS::GPS_OK_FIX_3D;
828
}
829
830
#if HAL_LOGGING_ENABLED
831
bool AP_GPS::should_log() const
832
{
833
AP_Logger *logger = AP_Logger::get_singleton();
834
if (logger == nullptr) {
835
return false;
836
}
837
if (_log_gps_bit == (uint32_t)-1) {
838
return false;
839
}
840
if (!logger->should_log(_log_gps_bit)) {
841
return false;
842
}
843
return true;
844
}
845
#endif
846
847
848
/*
849
update one GPS instance. This should be called at 10Hz or greater
850
*/
851
void AP_GPS::update_instance(uint8_t instance)
852
{
853
const auto type = params[instance].type;
854
if (type == GPS_TYPE_HIL) {
855
// in HIL, leave info alone
856
return;
857
}
858
if (type == GPS_TYPE_NONE) {
859
// not enabled
860
state[instance].status = NO_GPS;
861
state[instance].hdop = GPS_UNKNOWN_DOP;
862
state[instance].vdop = GPS_UNKNOWN_DOP;
863
return;
864
}
865
if (locked_ports & (1U<<instance)) {
866
// the port is locked by another driver
867
return;
868
}
869
870
if (drivers[instance] == nullptr) {
871
// we don't yet know the GPS type of this one, or it has timed
872
// out and needs to be re-initialised
873
detect_instance(instance);
874
return;
875
}
876
877
if (_auto_config >= GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY) {
878
send_blob_update(instance);
879
}
880
881
// we have an active driver for this instance
882
bool result = drivers[instance]->read();
883
uint32_t tnow = AP_HAL::millis();
884
885
// if we did not get a message, and the idle timer of 2 seconds
886
// has expired, re-initialise the GPS. This will cause GPS
887
// detection to run again
888
bool data_should_be_logged = false;
889
if (!result) {
890
if (tnow - timing[instance].last_message_time_ms > GPS_TIMEOUT_MS) {
891
memset((void *)&state[instance], 0, sizeof(state[instance]));
892
state[instance].instance = instance;
893
state[instance].hdop = GPS_UNKNOWN_DOP;
894
state[instance].vdop = GPS_UNKNOWN_DOP;
895
timing[instance].last_message_time_ms = tnow;
896
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
897
// do not try to detect again if type is MAV or UAVCAN
898
if (type == GPS_TYPE_MAV ||
899
type == GPS_TYPE_UAVCAN ||
900
type == GPS_TYPE_UAVCAN_RTK_BASE ||
901
type == GPS_TYPE_UAVCAN_RTK_ROVER) {
902
state[instance].status = NO_FIX;
903
} else {
904
// free the driver before we run the next detection, so we
905
// don't end up with two allocated at any time
906
delete drivers[instance];
907
drivers[instance] = nullptr;
908
state[instance].status = NO_GPS;
909
}
910
// log this data as a "flag" that the GPS is no longer
911
// valid (see PR#8144)
912
data_should_be_logged = true;
913
}
914
} else {
915
if (state[instance].corrected_timestamp_updated) {
916
// set the timestamp for this messages based on
917
// set_uart_timestamp() or per specific transport in backend
918
// , if available
919
tnow = state[instance].last_corrected_gps_time_us/1000U;
920
state[instance].corrected_timestamp_updated = false;
921
}
922
923
// announce the GPS type once
924
if (!state[instance].announced_detection) {
925
state[instance].announced_detection = true;
926
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: detected %s", instance + 1, drivers[instance]->name());
927
}
928
929
// delta will only be correct after parsing two messages
930
timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
931
timing[instance].last_message_time_ms = tnow;
932
// if GPS disabled for flight testing then don't update fix timing value
933
if (state[instance].status >= GPS_OK_FIX_2D && !_force_disable_gps) {
934
timing[instance].last_fix_time_ms = tnow;
935
}
936
937
data_should_be_logged = true;
938
}
939
940
#if GPS_MAX_RECEIVERS > 1
941
if (drivers[instance] && type == GPS_TYPE_UBLOX_RTK_BASE) {
942
// see if a moving baseline base has some RTCMv3 data
943
// which we need to pass along to the rover
944
const uint8_t *rtcm_data;
945
uint16_t rtcm_len;
946
if (drivers[instance]->get_RTCMV3(rtcm_data, rtcm_len)) {
947
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
948
if (i != instance && params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {
949
// pass the data to the rover
950
inject_data(i, rtcm_data, rtcm_len);
951
drivers[instance]->clear_RTCMV3();
952
break;
953
}
954
}
955
}
956
}
957
#endif
958
959
if (data_should_be_logged) {
960
// keep count of delayed frames and average frame delay for health reporting
961
const uint16_t gps_max_delta_ms = 245; // 200 ms (5Hz) + 45 ms buffer
962
GPS_timing &t = timing[instance];
963
964
if (t.delta_time_ms > gps_max_delta_ms) {
965
t.delayed_count++;
966
} else {
967
t.delayed_count = 0;
968
}
969
if (t.delta_time_ms < 2000) {
970
if (t.average_delta_ms <= 0) {
971
t.average_delta_ms = t.delta_time_ms;
972
} else {
973
t.average_delta_ms = 0.98f * t.average_delta_ms + 0.02f * t.delta_time_ms;
974
}
975
}
976
}
977
978
#if HAL_LOGGING_ENABLED
979
if (data_should_be_logged && should_log()) {
980
Write_GPS(instance);
981
}
982
#else
983
(void)data_should_be_logged;
984
#endif
985
986
#if AP_RTC_ENABLED
987
if (state[instance].status >= GPS_OK_FIX_3D) {
988
const uint64_t now = time_epoch_usec(instance);
989
if (now != 0) {
990
AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
991
}
992
}
993
#endif
994
}
995
996
997
#if GPS_MOVING_BASELINE
998
bool AP_GPS::get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading)
999
{
1000
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1001
if (drivers[i] &&
1002
state[i].relposheading_ts != 0 &&
1003
AP_HAL::millis() - state[i].relposheading_ts < 500) {
1004
relPosHeading = state[i].relPosHeading;
1005
relPosLength = state[i].relPosLength;
1006
relPosD = state[i].relPosD;
1007
accHeading = state[i].accHeading;
1008
timestamp = state[i].relposheading_ts;
1009
return true;
1010
}
1011
}
1012
return false;
1013
}
1014
1015
bool AP_GPS::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)
1016
{
1017
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1018
if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {
1019
return drivers[i]->get_RTCMV3(bytes, len);
1020
}
1021
}
1022
return false;
1023
}
1024
1025
void AP_GPS::clear_RTCMV3()
1026
{
1027
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1028
if (drivers[i] && params[i].type == GPS_TYPE_UBLOX_RTK_BASE) {
1029
drivers[i]->clear_RTCMV3();
1030
}
1031
}
1032
}
1033
1034
/*
1035
inject Moving Baseline Data messages.
1036
*/
1037
void AP_GPS::inject_MBL_data(uint8_t* data, uint16_t length)
1038
{
1039
for (uint8_t i=0; i< GPS_MAX_RECEIVERS; i++) {
1040
if (params[i].type == GPS_TYPE_UBLOX_RTK_ROVER) {
1041
// pass the data to the rover
1042
inject_data(i, data, length);
1043
break;
1044
}
1045
}
1046
}
1047
#endif //#if GPS_MOVING_BASELINE
1048
1049
/*
1050
update all GPS instances
1051
*/
1052
void AP_GPS::update(void)
1053
{
1054
WITH_SEMAPHORE(rsem);
1055
1056
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1057
update_instance(i);
1058
}
1059
1060
// calculate number of instances
1061
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1062
if (drivers[i] != nullptr) {
1063
num_instances = i+1;
1064
}
1065
}
1066
1067
#if GPS_MAX_RECEIVERS > 1
1068
#if HAL_LOGGING_ENABLED
1069
const uint8_t old_primary = primary_instance;
1070
#endif
1071
update_primary();
1072
#if HAL_LOGGING_ENABLED
1073
if (primary_instance != old_primary) {
1074
AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);
1075
}
1076
#endif // HAL_LOGING_ENABLED
1077
#endif // GPS_MAX_RECEIVERS > 1
1078
1079
#ifndef HAL_BUILD_AP_PERIPH
1080
// update notify with gps status. We always base this on the primary_instance
1081
AP_Notify::flags.gps_status = state[primary_instance].status;
1082
AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats;
1083
#endif
1084
}
1085
1086
/*
1087
update primary GPS instance
1088
*/
1089
#if GPS_MAX_RECEIVERS > 1
1090
void AP_GPS::update_primary(void)
1091
{
1092
#if AP_GPS_BLENDED_ENABLED
1093
/*
1094
if blending is requested, attempt to calculate weighting for
1095
each GPS
1096
we do not do blending if using moving baseline yaw as the rover is
1097
significant lagged and gives no more information on position or
1098
velocity
1099
*/
1100
const bool using_moving_base = is_rtk_base(0) || is_rtk_base(1);
1101
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) {
1102
_output_is_blended = ((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_weights();
1103
} else {
1104
_output_is_blended = false;
1105
((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->zero_health_counter();
1106
}
1107
1108
if (_output_is_blended) {
1109
// Use the weighting to calculate blended GPS states
1110
((AP_GPS_Blended*)drivers[GPS_BLENDED_INSTANCE])->calc_state();
1111
// set primary to the virtual instance
1112
primary_instance = GPS_BLENDED_INSTANCE;
1113
return;
1114
}
1115
#endif // AP_GPS_BLENDED_ENABLED
1116
1117
// check the primary param is set to possible GPS
1118
int8_t primary_param = _primary.get();
1119
if ((primary_param < 0) || (primary_param>=GPS_MAX_RECEIVERS)) {
1120
primary_param = 0;
1121
}
1122
// if primary is not enabled try first instance
1123
if (get_type(primary_param) == GPS_TYPE_NONE) {
1124
primary_param = 0;
1125
}
1126
1127
if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::NONE) {
1128
// No switching of GPSs, always use the primary instance
1129
primary_instance = primary_param;
1130
return;
1131
}
1132
1133
uint32_t now = AP_HAL::millis();
1134
1135
// special handling of RTK moving baseline pair. Always use the
1136
// base as the rover position is derived from the base, which
1137
// means the rover always has worse position and velocity than the
1138
// base. This overrides the normal logic which would select the
1139
// rover as it typically is in fix type 6 (RTK) whereas base is
1140
// usually fix type 3
1141
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1142
if (is_rtk_base(i) &&
1143
is_rtk_rover(i^1) &&
1144
((state[i].status >= GPS_OK_FIX_3D) || (state[i].status >= state[i^1].status))) {
1145
if (primary_instance != i) {
1146
_last_instance_swap_ms = now;
1147
primary_instance = i;
1148
}
1149
// don't do any more switching logic. We don't want the
1150
// RTK status of the rover to cause a switch
1151
return;
1152
}
1153
}
1154
1155
#if AP_GPS_BLENDED_ENABLED
1156
// handling switching away from blended GPS
1157
if (primary_instance == GPS_BLENDED_INSTANCE) {
1158
primary_instance = 0;
1159
for (uint8_t i=1; i<GPS_MAX_RECEIVERS; i++) {
1160
// choose GPS with highest state or higher number of
1161
// satellites. Reject a GPS with an old update time, as it
1162
// may be the old timestamp that triggered the loss of
1163
// blending
1164
const uint32_t delay_threshold = 400;
1165
const bool higher_status = state[i].status > state[primary_instance].status;
1166
const bool old_data_primary = (now - state[primary_instance].last_gps_time_ms) > delay_threshold;
1167
const bool old_data = (now - state[i].last_gps_time_ms) > delay_threshold;
1168
const bool equal_status = state[i].status == state[primary_instance].status;
1169
const bool more_sats = state[i].num_sats > state[primary_instance].num_sats;
1170
if (old_data && !old_data_primary) {
1171
// don't switch to a GPS that has not updated in 400ms
1172
continue;
1173
}
1174
if (state[i].status < GPS_OK_FIX_3D) {
1175
// don't use a GPS without 3D fix
1176
continue;
1177
}
1178
// select the new GPS if the primary has old data, or new
1179
// GPS either has higher status, or has the same status
1180
// and more satellites
1181
if ((old_data_primary && !old_data) ||
1182
higher_status ||
1183
(equal_status && more_sats)) {
1184
primary_instance = i;
1185
}
1186
}
1187
_last_instance_swap_ms = now;
1188
return;
1189
}
1190
#endif // AP_GPS_BLENDED_ENABLED
1191
1192
// Use primary if 3D fix or better
1193
if (((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::USE_PRIMARY_IF_3D_FIX) && (state[primary_param].status >= GPS_OK_FIX_3D)) {
1194
// Primary GPS has a least a 3D fix, switch to it if necessary
1195
if (primary_instance != primary_param) {
1196
primary_instance = primary_param;
1197
_last_instance_swap_ms = now;
1198
}
1199
return;
1200
}
1201
1202
// handle switch between real GPSs
1203
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1204
if (i == primary_instance) {
1205
continue;
1206
}
1207
if (state[i].status > state[primary_instance].status) {
1208
// we have a higher status lock, or primary is set to the blended GPS, change GPS
1209
primary_instance = i;
1210
_last_instance_swap_ms = now;
1211
continue;
1212
}
1213
1214
bool another_gps_has_1_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 1);
1215
1216
if (state[i].status == state[primary_instance].status && another_gps_has_1_or_more_sats) {
1217
1218
bool another_gps_has_2_or_more_sats = (state[i].num_sats >= state[primary_instance].num_sats + 2);
1219
1220
if ((another_gps_has_1_or_more_sats && (now - _last_instance_swap_ms) >= 20000) ||
1221
(another_gps_has_2_or_more_sats && (now - _last_instance_swap_ms) >= 5000)) {
1222
// this GPS has more satellites than the
1223
// current primary, switch primary. Once we switch we will
1224
// then tend to stick to the new GPS as primary. We don't
1225
// want to switch too often as it will look like a
1226
// position shift to the controllers.
1227
primary_instance = i;
1228
_last_instance_swap_ms = now;
1229
}
1230
}
1231
}
1232
}
1233
#endif // GPS_MAX_RECEIVERS > 1
1234
1235
#if HAL_GCS_ENABLED
1236
void AP_GPS::handle_gps_inject(const mavlink_message_t &msg)
1237
{
1238
mavlink_gps_inject_data_t packet;
1239
mavlink_msg_gps_inject_data_decode(&msg, &packet);
1240
1241
if (packet.len > sizeof(packet.data)) {
1242
// invalid packet
1243
return;
1244
}
1245
1246
handle_gps_rtcm_fragment(0, packet.data, packet.len);
1247
}
1248
1249
/*
1250
pass along a mavlink message (for MAV type)
1251
*/
1252
void AP_GPS::handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg)
1253
{
1254
switch (msg.msgid) {
1255
case MAVLINK_MSG_ID_GPS_RTCM_DATA:
1256
// pass data to de-fragmenter
1257
handle_gps_rtcm_data(chan, msg);
1258
break;
1259
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
1260
handle_gps_inject(msg);
1261
break;
1262
default: {
1263
uint8_t i;
1264
for (i=0; i<num_instances; i++) {
1265
if ((drivers[i] != nullptr) && (params[i].type != GPS_TYPE_NONE)) {
1266
drivers[i]->handle_msg(msg);
1267
}
1268
}
1269
break;
1270
}
1271
}
1272
}
1273
#endif
1274
1275
#if HAL_MSP_GPS_ENABLED
1276
void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt)
1277
{
1278
for (uint8_t i=0; i<num_instances; i++) {
1279
if (drivers[i] != nullptr && params[i].type == GPS_TYPE_MSP) {
1280
drivers[i]->handle_msp(pkt);
1281
}
1282
}
1283
}
1284
#endif // HAL_MSP_GPS_ENABLED
1285
1286
#if AP_EXTERNAL_AHRS_ENABLED
1287
1288
bool AP_GPS::get_first_external_instance(uint8_t& instance) const
1289
{
1290
for (uint8_t i=0; i<num_instances; i++) {
1291
if (drivers[i] != nullptr && params[i].type == GPS_TYPE_EXTERNAL_AHRS) {
1292
instance = i;
1293
return true;
1294
}
1295
}
1296
return false;
1297
}
1298
1299
void AP_GPS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance)
1300
{
1301
if (get_type(instance) == GPS_TYPE_EXTERNAL_AHRS && drivers[instance] != nullptr) {
1302
drivers[instance]->handle_external(pkt);
1303
}
1304
}
1305
#endif // AP_EXTERNAL_AHRS_ENABLED
1306
1307
/**
1308
Lock a GPS port, preventing the GPS driver from using it. This can
1309
be used to allow a user to control a GPS port via the
1310
SERIAL_CONTROL protocol
1311
*/
1312
void AP_GPS::lock_port(uint8_t instance, bool lock)
1313
{
1314
1315
if (instance >= GPS_MAX_RECEIVERS) {
1316
return;
1317
}
1318
if (lock) {
1319
locked_ports |= (1U<<instance);
1320
} else {
1321
locked_ports &= ~(1U<<instance);
1322
}
1323
}
1324
1325
// Inject a packet of raw binary to a GPS
1326
void AP_GPS::inject_data(const uint8_t *data, uint16_t len)
1327
{
1328
//Support broadcasting to all GPSes.
1329
if (_inject_to == GPS_RTK_INJECT_TO_ALL) {
1330
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
1331
if (is_rtk_rover(i)) {
1332
// we don't externally inject to moving baseline rover
1333
continue;
1334
}
1335
inject_data(i, data, len);
1336
}
1337
} else {
1338
inject_data(_inject_to, data, len);
1339
}
1340
}
1341
1342
void AP_GPS::inject_data(uint8_t instance, const uint8_t *data, uint16_t len)
1343
{
1344
if (instance < GPS_MAX_RECEIVERS && drivers[instance] != nullptr) {
1345
drivers[instance]->inject_data(data, len);
1346
}
1347
}
1348
1349
/*
1350
get GPS yaw following mavlink GPS_RAW_INT and GPS2_RAW
1351
convention. We return 0 if the GPS is not configured to provide
1352
yaw. We return 65535 for a GPS configured to provide yaw that can't
1353
currently provide it. We return from 1 to 36000 for yaw otherwise
1354
*/
1355
uint16_t AP_GPS::gps_yaw_cdeg(uint8_t instance) const
1356
{
1357
if (!have_gps_yaw_configured(instance)) {
1358
return 0;
1359
}
1360
float yaw_deg, accuracy_deg;
1361
uint32_t time_ms;
1362
if (!gps_yaw_deg(instance, yaw_deg, accuracy_deg, time_ms)) {
1363
return 65535;
1364
}
1365
int yaw_cd = wrap_360_cd(yaw_deg * 100);
1366
if (yaw_cd == 0) {
1367
return 36000;
1368
}
1369
return yaw_cd;
1370
}
1371
1372
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
1373
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
1374
{
1375
// Only send if enabled
1376
if (get_type(0) == GPS_TYPE_NONE) {
1377
return;
1378
}
1379
1380
const Location &loc = location(0);
1381
float hacc = 0.0f;
1382
float vacc = 0.0f;
1383
float sacc = 0.0f;
1384
float undulation = 0.0;
1385
int32_t height_elipsoid_mm = 0;
1386
if (get_undulation(0, undulation)) {
1387
height_elipsoid_mm = loc.alt*10 - undulation*1000;
1388
}
1389
horizontal_accuracy(0, hacc);
1390
vertical_accuracy(0, vacc);
1391
speed_accuracy(0, sacc);
1392
mavlink_msg_gps_raw_int_send(
1393
chan,
1394
last_fix_time_ms(0)*(uint64_t)1000,
1395
status(0),
1396
loc.lat, // in 1E7 degrees
1397
loc.lng, // in 1E7 degrees
1398
loc.alt * 10UL, // in mm
1399
get_hdop(0),
1400
get_vdop(0),
1401
ground_speed(0)*100, // cm/s
1402
ground_course(0)*100, // 1/100 degrees,
1403
num_sats(0),
1404
height_elipsoid_mm, // Ellipsoid height in mm
1405
hacc * 1000, // one-sigma standard deviation in mm
1406
vacc * 1000, // one-sigma standard deviation in mm
1407
sacc * 1000, // one-sigma standard deviation in mm/s
1408
0, // TODO one-sigma heading accuracy standard deviation
1409
gps_yaw_cdeg(0));
1410
}
1411
#endif // AP_GPS_GPS_RAW_INT_SENDING_ENABLED
1412
1413
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
1414
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
1415
{
1416
// always send the message if 2nd GPS is configured
1417
if (params[1].type == GPS_TYPE_NONE) {
1418
return;
1419
}
1420
1421
const Location &loc = location(1);
1422
float hacc = 0.0f;
1423
float vacc = 0.0f;
1424
float sacc = 0.0f;
1425
float undulation = 0.0;
1426
float height_elipsoid_mm = 0;
1427
if (get_undulation(1, undulation)) {
1428
height_elipsoid_mm = loc.alt*10 - undulation*1000;
1429
}
1430
horizontal_accuracy(1, hacc);
1431
vertical_accuracy(1, vacc);
1432
speed_accuracy(1, sacc);
1433
mavlink_msg_gps2_raw_send(
1434
chan,
1435
last_fix_time_ms(1)*(uint64_t)1000,
1436
status(1),
1437
loc.lat,
1438
loc.lng,
1439
loc.alt * 10UL,
1440
get_hdop(1),
1441
get_vdop(1),
1442
ground_speed(1)*100, // cm/s
1443
ground_course(1)*100, // 1/100 degrees,
1444
num_sats(1),
1445
state[1].rtk_num_sats,
1446
state[1].rtk_age_ms,
1447
gps_yaw_cdeg(1),
1448
height_elipsoid_mm, // Ellipsoid height in mm
1449
hacc * 1000, // one-sigma standard deviation in mm
1450
vacc * 1000, // one-sigma standard deviation in mm
1451
sacc * 1000, // one-sigma standard deviation in mm/s
1452
0); // TODO one-sigma heading accuracy standard deviation
1453
}
1454
#endif // AP_GPS_GPS2_RAW_SENDING_ENABLED
1455
1456
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
1457
void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst)
1458
{
1459
if (inst >= GPS_MAX_RECEIVERS) {
1460
return;
1461
}
1462
if (drivers[inst] != nullptr && drivers[inst]->supports_mavlink_gps_rtk_message()) {
1463
drivers[inst]->send_mavlink_gps_rtk(chan);
1464
}
1465
}
1466
#endif
1467
1468
bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const
1469
{
1470
for (int i = 0; i < GPS_MAX_RECEIVERS; i++) {
1471
if (params[i].type != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) {
1472
instance = i;
1473
return true;
1474
}
1475
}
1476
return false;
1477
}
1478
1479
void AP_GPS::broadcast_first_configuration_failure_reason(void) const
1480
{
1481
uint8_t unconfigured;
1482
if (first_unconfigured_gps(unconfigured)) {
1483
if (drivers[unconfigured] == nullptr) {
1484
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1);
1485
} else {
1486
drivers[unconfigured]->broadcast_configuration_failure_reason();
1487
}
1488
}
1489
}
1490
1491
// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
1492
bool AP_GPS::all_consistent(float &distance) const
1493
{
1494
// return true immediately if only one valid receiver
1495
if (num_instances <= 1 ||
1496
drivers[0] == nullptr || params[0].type == GPS_TYPE_NONE) {
1497
distance = 0;
1498
return true;
1499
}
1500
1501
// calculate distance
1502
distance = state[0].location.get_distance_NED(state[1].location).length();
1503
// success if distance is within 50m
1504
return (distance < 50);
1505
}
1506
1507
/*
1508
re-assemble fragmented RTCM data
1509
*/
1510
void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len)
1511
{
1512
if ((flags & 1) == 0) {
1513
// it is not fragmented, pass direct
1514
inject_data(data, len);
1515
return;
1516
}
1517
1518
// see if we need to allocate re-assembly buffer
1519
if (rtcm_buffer == nullptr) {
1520
rtcm_buffer = (struct rtcm_buffer *)calloc(1, sizeof(*rtcm_buffer));
1521
if (rtcm_buffer == nullptr) {
1522
// nothing to do but discard the data
1523
return;
1524
}
1525
}
1526
1527
const uint8_t fragment = (flags >> 1U) & 0x03;
1528
const uint8_t sequence = (flags >> 3U) & 0x1F;
1529
uint8_t* start_of_fragment_in_buffer = &rtcm_buffer->buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN * (uint16_t)fragment];
1530
bool should_clear_previous_fragments = false;
1531
1532
if (rtcm_buffer->fragments_received) {
1533
const bool sequence_nr_changed = rtcm_buffer->sequence != sequence;
1534
const bool seen_this_fragment_index = rtcm_buffer->fragments_received & (1U << fragment);
1535
1536
// check whether this is a duplicate fragment. If it is, we can
1537
// return early.
1538
if (!sequence_nr_changed && seen_this_fragment_index && !memcmp(start_of_fragment_in_buffer, data, len)) {
1539
return;
1540
}
1541
1542
// not a duplicate
1543
should_clear_previous_fragments = sequence_nr_changed || seen_this_fragment_index;
1544
}
1545
1546
if (should_clear_previous_fragments) {
1547
// we have one or more partial fragments already received
1548
// which conflict with the new fragment, discard previous fragments
1549
rtcm_buffer->fragment_count = 0;
1550
rtcm_stats.fragments_discarded += __builtin_popcount(rtcm_buffer->fragments_received);
1551
rtcm_buffer->fragments_received = 0;
1552
}
1553
1554
// add this fragment
1555
rtcm_buffer->sequence = sequence;
1556
rtcm_buffer->fragments_received |= (1U << fragment);
1557
1558
// copy the data
1559
memcpy(start_of_fragment_in_buffer, data, len);
1560
1561
// when we get a fragment of less than max size then we know the
1562
// number of fragments. Note that this means if you want to send a
1563
// block of RTCM data of an exact multiple of the buffer size you
1564
// need to send a final packet of zero length
1565
if (len < MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN) {
1566
rtcm_buffer->fragment_count = fragment+1;
1567
rtcm_buffer->total_length = (MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*fragment) + len;
1568
} else if (rtcm_buffer->fragments_received == 0x0F) {
1569
// special case of 4 full fragments
1570
rtcm_buffer->fragment_count = 4;
1571
rtcm_buffer->total_length = MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4;
1572
}
1573
1574
1575
// see if we have all fragments
1576
if (rtcm_buffer->fragment_count != 0 &&
1577
rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
1578
// we have them all, inject
1579
rtcm_stats.fragments_used += __builtin_popcount(rtcm_buffer->fragments_received);
1580
inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);
1581
rtcm_buffer->fragment_count = 0;
1582
rtcm_buffer->fragments_received = 0;
1583
}
1584
}
1585
1586
/*
1587
re-assemble GPS_RTCM_DATA message
1588
*/
1589
void AP_GPS::handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_t &msg)
1590
{
1591
mavlink_gps_rtcm_data_t packet;
1592
mavlink_msg_gps_rtcm_data_decode(&msg, &packet);
1593
1594
if (packet.len > sizeof(packet.data)) {
1595
// invalid packet
1596
return;
1597
}
1598
1599
#if AP_GPS_RTCM_DECODE_ENABLED
1600
if (!option_set(DriverOptions::DisableRTCMDecode)) {
1601
const uint16_t mask = (1U << unsigned(chan));
1602
rtcm.seen_mav_channels |= mask;
1603
if (option_set(DriverOptions::AlwaysRTCMDecode) ||
1604
(rtcm.seen_mav_channels & ~mask) != 0) {
1605
/*
1606
we are seeing RTCM on multiple mavlink channels. We will run
1607
the data through a full per-channel RTCM decoder
1608
*/
1609
if (parse_rtcm_injection(chan, packet)) {
1610
return;
1611
}
1612
}
1613
}
1614
#endif
1615
1616
handle_gps_rtcm_fragment(packet.flags, packet.data, packet.len);
1617
}
1618
1619
#if AP_GPS_RTCM_DECODE_ENABLED
1620
/*
1621
fully parse RTCM data coming in from a MAVLink channel, when we have
1622
a full message inject it to the GPS. This approach allows for 2 or
1623
more MAVLink channels to be used for the same RTCM data, allowing
1624
for redundent transports for maximum reliability at the cost of some
1625
extra CPU and a bit of re-assembly lag
1626
*/
1627
bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt)
1628
{
1629
if (static_cast<int>(chan) >= MAVLINK_COMM_NUM_BUFFERS) {
1630
return false;
1631
}
1632
if (rtcm.parsers[chan] == nullptr) {
1633
rtcm.parsers[chan] = NEW_NOTHROW RTCM3_Parser();
1634
if (rtcm.parsers[chan] == nullptr) {
1635
return false;
1636
}
1637
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS: RTCM parsing for chan %u", unsigned(chan));
1638
}
1639
for (uint16_t i=0; i<pkt.len; i++) {
1640
if (rtcm.parsers[chan]->read(pkt.data[i])) {
1641
// we have a full message, inject it
1642
const uint8_t *buf = nullptr;
1643
uint16_t len = rtcm.parsers[chan]->get_len(buf);
1644
1645
// see if we have already sent it. This prevents
1646
// duplicates from multiple sources
1647
const uint32_t crc = crc_crc32(0, buf, len);
1648
1649
#if HAL_LOGGING_ENABLED
1650
// @LoggerMessage: RTCM
1651
// @Description: GPS atmospheric perturbation data
1652
// @Field: TimeUS: Time since system startup
1653
// @Field: Chan: mavlink channel number this data was received on
1654
// @Field: RTCMId: ID field from RTCM packet
1655
// @Field: Len: RTCM packet length
1656
// @Field: CRC: calculated crc32 for the packet
1657
AP::logger().WriteStreaming("RTCM", "TimeUS,Chan,RTCMId,Len,CRC", "s#---", "F----", "QBHHI",
1658
AP_HAL::micros64(),
1659
uint8_t(chan),
1660
rtcm.parsers[chan]->get_id(),
1661
len,
1662
crc);
1663
#endif
1664
1665
bool already_seen = false;
1666
for (uint8_t c=0; c<ARRAY_SIZE(rtcm.sent_crc); c++) {
1667
if (rtcm.sent_crc[c] == crc) {
1668
// we have already sent this message
1669
already_seen = true;
1670
break;
1671
}
1672
}
1673
if (already_seen) {
1674
continue;
1675
}
1676
rtcm.sent_crc[rtcm.sent_idx] = crc;
1677
rtcm.sent_idx = (rtcm.sent_idx+1) % ARRAY_SIZE(rtcm.sent_crc);
1678
1679
if (buf != nullptr && len > 0) {
1680
inject_data(buf, len);
1681
}
1682
rtcm.parsers[chan]->reset();
1683
}
1684
}
1685
return true;
1686
}
1687
#endif // AP_GPS_RTCM_DECODE_ENABLED
1688
1689
#if HAL_LOGGING_ENABLED
1690
void AP_GPS::Write_AP_Logger_Log_Startup_messages()
1691
{
1692
for (uint8_t instance=0; instance<num_instances; instance++) {
1693
if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1694
continue;
1695
}
1696
drivers[instance]->Write_AP_Logger_Log_Startup_messages();
1697
}
1698
}
1699
#endif
1700
1701
/*
1702
return the expected lag (in seconds) in the position and velocity readings from the gps
1703
return true if the GPS hardware configuration is known or the delay parameter has been set
1704
*/
1705
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
1706
{
1707
// always ensure a lag is provided
1708
lag_sec = 0.1f;
1709
1710
if (instance >= GPS_MAX_INSTANCES) {
1711
return false;
1712
}
1713
1714
#if AP_GPS_BLENDED_ENABLED
1715
// return lag of blended GPS
1716
if (instance == GPS_BLENDED_INSTANCE) {
1717
return drivers[instance]->get_lag(lag_sec);
1718
}
1719
#endif
1720
1721
if (params[instance].delay_ms > 0) {
1722
// if the user has specified a non zero time delay, always return that value
1723
lag_sec = 0.001f * (float)params[instance].delay_ms;
1724
// the user is always right !!
1725
return true;
1726
} else if (drivers[instance] == nullptr || state[instance].status == NO_GPS) {
1727
// no GPS was detected in this instance so return the worst possible lag term
1728
const auto type = params[instance].type;
1729
if (type == GPS_TYPE_NONE) {
1730
lag_sec = 0.0f;
1731
return true;
1732
}
1733
return type == GPS_TYPE_AUTO;
1734
} else {
1735
// the user has not specified a delay so we determine it from the GPS type
1736
return drivers[instance]->get_lag(lag_sec);
1737
}
1738
}
1739
1740
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
1741
const Vector3f &AP_GPS::get_antenna_offset(uint8_t instance) const
1742
{
1743
if (instance >= GPS_MAX_INSTANCES) {
1744
// we have to return a reference so use instance 0
1745
return params[0].antenna_offset;
1746
}
1747
1748
#if AP_GPS_BLENDED_ENABLED
1749
if (instance == GPS_BLENDED_INSTANCE) {
1750
// return an offset for the blended GPS solution
1751
return ((AP_GPS_Blended*)drivers[instance])->get_antenna_offset();
1752
}
1753
#endif
1754
1755
return params[instance].antenna_offset;
1756
}
1757
1758
/*
1759
returns the desired gps update rate in milliseconds
1760
this does not provide any guarantee that the GPS is updating at the requested
1761
rate it is simply a helper for use in the backends for determining what rate
1762
they should be configuring the GPS to run at
1763
*/
1764
uint16_t AP_GPS::get_rate_ms(uint8_t instance) const
1765
{
1766
// sanity check
1767
if (instance >= num_instances || params[instance].rate_ms <= 0) {
1768
return GPS_MAX_RATE_MS;
1769
}
1770
return MIN(params[instance].rate_ms, GPS_MAX_RATE_MS);
1771
}
1772
1773
bool AP_GPS::is_healthy(uint8_t instance) const
1774
{
1775
if (instance >= GPS_MAX_INSTANCES) {
1776
return false;
1777
}
1778
1779
if (get_type(_primary.get()) == GPS_TYPE_NONE) {
1780
return false;
1781
}
1782
1783
#ifndef HAL_BUILD_AP_PERIPH
1784
/*
1785
on AP_Periph handling of timing is done by the flight controller
1786
receiving the DroneCAN messages
1787
*/
1788
/*
1789
allow two lost frames before declaring the GPS unhealthy, but
1790
require the average frame rate to be close to 5Hz.
1791
1792
We allow for a rate of 3Hz average for a moving baseline rover
1793
due to the packet loss that happens with the RTCMv3 data and the
1794
fact that the rate of yaw data is not critical
1795
*/
1796
const uint8_t delay_threshold = 2;
1797
const float delay_avg_max = is_rtk_rover(instance) ? 333 : 215;
1798
const GPS_timing &t = timing[instance];
1799
bool delay_ok = (t.delayed_count < delay_threshold) &&
1800
t.average_delta_ms < delay_avg_max &&
1801
state[instance].lagged_sample_count < 5;
1802
if (!delay_ok) {
1803
return false;
1804
}
1805
#endif // HAL_BUILD_AP_PERIPH
1806
1807
return drivers[instance] != nullptr &&
1808
drivers[instance]->is_healthy();
1809
}
1810
1811
bool AP_GPS::prepare_for_arming(void) {
1812
bool all_passed = true;
1813
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1814
if (drivers[i] != nullptr) {
1815
all_passed &= drivers[i]->prepare_for_arming();
1816
}
1817
}
1818
return all_passed;
1819
}
1820
1821
bool AP_GPS::pre_arm_checks(char failure_msg[], uint16_t failure_msg_len)
1822
{
1823
// the DroneCAN class has additional checks for DroneCAN-specific
1824
// parameters:
1825
#if AP_GPS_DRONECAN_ENABLED
1826
if (!AP_GPS_DroneCAN::inter_instance_pre_arm_checks(failure_msg, failure_msg_len)) {
1827
return false;
1828
}
1829
#endif
1830
1831
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1832
if (is_rtk_rover(i)) {
1833
if (AP_HAL::millis() - state[i].gps_yaw_time_ms > 15000) {
1834
hal.util->snprintf(failure_msg, failure_msg_len, "GPS[%u] yaw not available", unsigned(i+1));
1835
return false;
1836
}
1837
}
1838
}
1839
1840
#if AP_GPS_BLENDED_ENABLED
1841
if (!drivers[GPS_BLENDED_INSTANCE]->is_healthy()) {
1842
hal.util->snprintf(failure_msg, failure_msg_len, "GPS blending unhealthy");
1843
return false;
1844
}
1845
#endif
1846
1847
return true;
1848
}
1849
1850
bool AP_GPS::logging_failed(void) const {
1851
if (!logging_enabled()) {
1852
return false;
1853
}
1854
1855
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
1856
if ((drivers[i] != nullptr) && !(drivers[i]->logging_healthy())) {
1857
return true;
1858
}
1859
}
1860
1861
return false;
1862
}
1863
1864
// get iTOW, if supported, zero otherwie
1865
uint32_t AP_GPS::get_itow(uint8_t instance) const
1866
{
1867
if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {
1868
return 0;
1869
}
1870
return drivers[instance]->get_last_itow_ms();
1871
}
1872
1873
bool AP_GPS::get_error_codes(uint8_t instance, uint32_t &error_codes) const
1874
{
1875
if (instance >= GPS_MAX_RECEIVERS || drivers[instance] == nullptr) {
1876
return false;
1877
}
1878
1879
return drivers[instance]->get_error_codes(error_codes);
1880
}
1881
1882
// get the difference between WGS84 and AMSL. A positive value means
1883
// the AMSL height is higher than WGS84 ellipsoid height
1884
bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const
1885
{
1886
if (!state[instance].have_undulation) {
1887
return false;
1888
}
1889
undulation = state[instance].undulation;
1890
return true;
1891
}
1892
1893
#if HAL_LOGGING_ENABLED
1894
// Logging support:
1895
// Write an GPS packet
1896
void AP_GPS::Write_GPS(uint8_t i)
1897
{
1898
const uint64_t time_us = AP_HAL::micros64();
1899
const Location &loc = location(i);
1900
1901
float yaw_deg=0, yaw_accuracy_deg=0;
1902
uint32_t yaw_time_ms;
1903
gps_yaw_deg(i, yaw_deg, yaw_accuracy_deg, yaw_time_ms);
1904
1905
const struct log_GPS pkt {
1906
LOG_PACKET_HEADER_INIT(LOG_GPS_MSG),
1907
time_us : time_us,
1908
instance : i,
1909
status : (uint8_t)status(i),
1910
gps_week_ms : time_week_ms(i),
1911
gps_week : time_week(i),
1912
num_sats : num_sats(i),
1913
hdop : get_hdop(i),
1914
latitude : loc.lat,
1915
longitude : loc.lng,
1916
altitude : loc.alt,
1917
ground_speed : ground_speed(i),
1918
ground_course : ground_course(i),
1919
vel_z : velocity(i).z,
1920
yaw : yaw_deg,
1921
used : (uint8_t)(AP::gps().primary_sensor() == i)
1922
};
1923
AP::logger().WriteBlock(&pkt, sizeof(pkt));
1924
1925
/* write auxiliary accuracy information as well */
1926
float hacc = 0, vacc = 0, sacc = 0;
1927
int32_t alt_ellipsoid = INT32_MIN;
1928
float undulation = 0;
1929
horizontal_accuracy(i, hacc);
1930
vertical_accuracy(i, vacc);
1931
speed_accuracy(i, sacc);
1932
if (get_undulation(i, undulation)) {
1933
alt_ellipsoid = loc.alt - (undulation*100);
1934
}
1935
struct log_GPA pkt2{
1936
LOG_PACKET_HEADER_INIT(LOG_GPA_MSG),
1937
time_us : time_us,
1938
instance : i,
1939
vdop : get_vdop(i),
1940
hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),
1941
vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
1942
sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
1943
yaw_accuracy : yaw_accuracy_deg,
1944
have_vv : (uint8_t)have_vertical_velocity(i),
1945
sample_ms : last_message_time_ms(i),
1946
delta_ms : last_message_delta_time_ms(i),
1947
alt_ellipsoid : alt_ellipsoid,
1948
rtcm_fragments_used: rtcm_stats.fragments_used,
1949
rtcm_fragments_discarded: rtcm_stats.fragments_discarded
1950
};
1951
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
1952
}
1953
#endif
1954
1955
bool AP_GPS::is_rtk_base(uint8_t instance) const
1956
{
1957
switch (get_type(instance)) {
1958
case GPS_TYPE_UBLOX_RTK_BASE:
1959
case GPS_TYPE_UAVCAN_RTK_BASE:
1960
return true;
1961
default:
1962
break;
1963
}
1964
return false;
1965
}
1966
1967
bool AP_GPS::is_rtk_rover(uint8_t instance) const
1968
{
1969
switch (get_type(instance)) {
1970
case GPS_TYPE_UBLOX_RTK_ROVER:
1971
case GPS_TYPE_UAVCAN_RTK_ROVER:
1972
return true;
1973
default:
1974
break;
1975
}
1976
return false;
1977
}
1978
1979
/*
1980
get GPS based yaw
1981
*/
1982
bool AP_GPS::gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const
1983
{
1984
#if GPS_MAX_RECEIVERS > 1
1985
if (is_rtk_base(instance) && is_rtk_rover(instance^1)) {
1986
// return the yaw from the rover
1987
instance ^= 1;
1988
}
1989
#endif
1990
if (!have_gps_yaw(instance)) {
1991
return false;
1992
}
1993
yaw_deg = state[instance].gps_yaw;
1994
1995
// get lagged timestamp
1996
time_ms = state[instance].gps_yaw_time_ms;
1997
float lag_s;
1998
if (get_lag(instance, lag_s)) {
1999
uint32_t lag_ms = lag_s * 1000;
2000
time_ms -= lag_ms;
2001
}
2002
2003
if (state[instance].have_gps_yaw_accuracy) {
2004
accuracy_deg = state[instance].gps_yaw_accuracy;
2005
} else {
2006
// fall back to 10 degrees as a generic default
2007
accuracy_deg = 10;
2008
}
2009
return true;
2010
}
2011
2012
/*
2013
* Old parameter metadata. Until we have versioned parameters, keeping
2014
* old parameters around for a while can help with an adjustment
2015
* period.
2016
*/
2017
2018
// @Param: _TYPE
2019
// @DisplayName: 1st GPS type
2020
// @Description: GPS type of 1st GPS.Renamed in 4.6 and later to GPS1_TYPE
2021
// @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
2022
// @RebootRequired: True
2023
// @User: Advanced
2024
// @Legacy: only included here so GCSs running stable can get the description. Omitted in the Wiki.
2025
2026
// @Param: _TYPE2
2027
// @CopyFieldsFrom: GPS_TYPE
2028
// @DisplayName: 2nd GPS type.Renamed in 4.6 to GPS2_TYPE
2029
// @Description: GPS type of 2nd GPS
2030
// @Legacy: 4.5 param
2031
2032
// @Param: _GNSS_MODE
2033
// @DisplayName: GNSS system configuration
2034
// @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.
2035
// @Legacy: 4.5 param
2036
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
2037
// @User: Advanced
2038
2039
// @Param: _GNSS_MODE2
2040
// @DisplayName: GNSS system configuration.
2041
// @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
2042
// @Legacy: 4.5 param
2043
// @Bitmask: 0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLONASS
2044
// @User: Advanced
2045
2046
// @Param: _RATE_MS
2047
// @DisplayName: GPS update rate in milliseconds
2048
// @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
2049
// @Legacy: 4.5 param
2050
// @Units: ms
2051
// @Values: 100:10Hz,125:8Hz,200:5Hz
2052
// @Range: 50 200
2053
// @User: Advanced
2054
2055
// @Param: _RATE_MS2
2056
// @DisplayName: GPS 2 update rate in milliseconds
2057
// @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
2058
// @Legacy: 4.5 param
2059
// @Units: ms
2060
// @Values: 100:10Hz,125:8Hz,200:5Hz
2061
// @Range: 50 200
2062
// @User: Advanced
2063
2064
// @Param: _POS1_X
2065
// @DisplayName: Antenna X position offset
2066
// @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.
2067
// @Legacy: 4.5 param
2068
// @Units: m
2069
// @Range: -5 5
2070
// @Increment: 0.01
2071
// @User: Advanced
2072
2073
// @Param: _POS1_Y
2074
// @DisplayName: Antenna Y position offset
2075
// @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.
2076
// @Legacy: 4.5 param
2077
// @Units: m
2078
// @Range: -5 5
2079
// @Increment: 0.01
2080
// @User: Advanced
2081
2082
// @Param: _POS1_Z
2083
// @DisplayName: Antenna Z position offset
2084
// @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.
2085
// @Legacy: 4.5 param
2086
// @Units: m
2087
// @Range: -5 5
2088
// @Increment: 0.01
2089
// @User: Advanced
2090
2091
// @Param: _POS2_X
2092
// @DisplayName: Antenna X position offset
2093
// @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.
2094
// @Legacy: 4.5 param
2095
// @Units: m
2096
// @Range: -5 5
2097
// @Increment: 0.01
2098
// @User: Advanced
2099
2100
// @Param: _POS2_Y
2101
// @DisplayName: Antenna Y position offset
2102
// @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.
2103
// @Legacy: 4.5 param
2104
// @Units: m
2105
// @Range: -5 5
2106
// @Increment: 0.01
2107
// @User: Advanced
2108
2109
// @Param: _POS2_Z
2110
// @DisplayName: Antenna Z position offset
2111
// @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.
2112
// @Legacy: 4.5 param
2113
// @Units: m
2114
// @Range: -5 5
2115
// @Increment: 0.01
2116
// @User: Advanced
2117
2118
// @Param: _DELAY_MS
2119
// @DisplayName: GPS delay in milliseconds
2120
// @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.
2121
// @Legacy: 4.5 param
2122
// @Units: ms
2123
// @Range: 0 250
2124
// @User: Advanced
2125
// @RebootRequired: True
2126
2127
// @Param: _DELAY_MS2
2128
// @DisplayName: GPS 2 delay in milliseconds
2129
// @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.
2130
// @Legacy: 4.5 param
2131
// @Units: ms
2132
// @Range: 0 250
2133
// @User: Advanced
2134
// @RebootRequired: True
2135
2136
// @Param: _COM_PORT
2137
// @DisplayName: GPS physical COM port
2138
// @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.
2139
// @Legacy: 4.5 param
2140
// @Range: 0 10
2141
// @Increment: 1
2142
// @User: Advanced
2143
// @Values: 0:COM1(RS232) on GSOF, 1:COM2(TTL) on GSOF
2144
// @RebootRequired: True
2145
2146
// @Param: _COM_PORT2
2147
// @DisplayName: GPS physical COM port
2148
// @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.
2149
// @Legacy: 4.5 param
2150
// @Range: 0 10
2151
// @Increment: 1
2152
// @User: Advanced
2153
// @RebootRequired: True
2154
2155
// @Group: _MB1_
2156
// @Path: MovingBase.cpp
2157
// @Legacy: 4.5 param
2158
2159
// @Group: _MB2_
2160
// @Path: MovingBase.cpp
2161
// @Legacy: 4.5 param
2162
2163
// @Param: _CAN_NODEID1
2164
// @DisplayName: GPS Node ID 1
2165
// @Description: GPS Node id for first-discovered GPS.Renamed in 4.6 and later to GPS1_CAN_NODEID.
2166
// @Legacy: 4.5 param
2167
// @ReadOnly: True
2168
// @User: Advanced
2169
2170
// @Param: _CAN_NODEID2
2171
// @DisplayName: GPS Node ID 2
2172
// @Description: GPS Node id for second-discovered GPS.Renamed in 4.6 and later to GPS2_CAN_NODEID.
2173
// @Legacy: 4.5 param
2174
// @ReadOnly: True
2175
// @User: Advanced
2176
2177
/*
2178
* end old parameter metadata
2179
*/
2180
2181
namespace AP {
2182
2183
AP_GPS &gps()
2184
{
2185
return *AP_GPS::get_singleton();
2186
}
2187
2188
};
2189
2190
#endif // AP_GPS_ENABLED
2191
2192