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.h
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
#pragma once
16
17
#include "AP_GPS_config.h"
18
19
#if AP_GPS_ENABLED
20
21
#include <AP_HAL/AP_HAL.h>
22
#include <inttypes.h>
23
#include <AP_Common/AP_Common.h>
24
#include <AP_Common/Location.h>
25
#include <AP_Param/AP_Param.h>
26
#include "GPS_detect_state.h"
27
#include <AP_Math/AP_Math.h>
28
#include <AP_MSP/msp.h>
29
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
30
#include <SITL/SIM_GPS.h>
31
#include <GCS_MAVLink/GCS_MAVLink.h>
32
33
#define GPS_UNKNOWN_DOP UINT16_MAX // set unknown DOP's to maximum value, which is also correct for MAVLink
34
35
// the number of GPS leap seconds - copied into SIM_GPS.cpp
36
#define GPS_LEAPSECONDS_MILLIS 18000ULL
37
38
#define UNIX_OFFSET_MSEC (17000ULL * 86400ULL + 52ULL * 10ULL * AP_MSEC_PER_WEEK - GPS_LEAPSECONDS_MILLIS)
39
40
#ifndef GPS_MOVING_BASELINE
41
#define GPS_MOVING_BASELINE GPS_MAX_RECEIVERS>1
42
#endif
43
44
#if GPS_MOVING_BASELINE
45
#include "MovingBase.h"
46
#endif // GPS_MOVING_BASELINE
47
48
class AP_GPS_Backend;
49
class RTCM3_Parser;
50
51
/// @class AP_GPS
52
/// GPS driver main class
53
class AP_GPS
54
{
55
friend class AP_GPS_Blended;
56
friend class AP_GPS_ERB;
57
friend class AP_GPS_GSOF;
58
friend class AP_GPS_MAV;
59
friend class AP_GPS_MSP;
60
friend class AP_GPS_ExternalAHRS;
61
friend class AP_GPS_NMEA;
62
friend class AP_GPS_NOVA;
63
friend class AP_GPS_PX4;
64
friend class AP_GPS_SBF;
65
friend class AP_GPS_SBP;
66
friend class AP_GPS_SBP2;
67
friend class AP_GPS_SIRF;
68
friend class AP_GPS_UBLOX;
69
friend class AP_GPS_Backend;
70
friend class AP_GPS_DroneCAN;
71
72
public:
73
AP_GPS();
74
75
/* Do not allow copies */
76
CLASS_NO_COPY(AP_GPS);
77
78
static AP_GPS *get_singleton() {
79
return _singleton;
80
}
81
82
// allow threads to lock against GPS update
83
HAL_Semaphore &get_semaphore(void) {
84
return rsem;
85
}
86
87
// GPS driver types
88
enum GPS_Type {
89
GPS_TYPE_NONE = 0,
90
GPS_TYPE_AUTO = 1,
91
GPS_TYPE_UBLOX = 2,
92
// GPS_TYPE_MTK = 3, // driver removed
93
// GPS_TYPE_MTK19 = 4, // driver removed
94
GPS_TYPE_NMEA = 5,
95
GPS_TYPE_SIRF = 6,
96
GPS_TYPE_HIL = 7,
97
GPS_TYPE_SBP = 8,
98
GPS_TYPE_UAVCAN = 9,
99
GPS_TYPE_SBF = 10,
100
GPS_TYPE_GSOF = 11,
101
GPS_TYPE_ERB = 13,
102
GPS_TYPE_MAV = 14,
103
GPS_TYPE_NOVA = 15,
104
GPS_TYPE_HEMI = 16, // hemisphere NMEA
105
GPS_TYPE_UBLOX_RTK_BASE = 17,
106
GPS_TYPE_UBLOX_RTK_ROVER = 18,
107
GPS_TYPE_MSP = 19,
108
GPS_TYPE_ALLYSTAR = 20, // AllyStar NMEA
109
GPS_TYPE_EXTERNAL_AHRS = 21,
110
GPS_TYPE_UAVCAN_RTK_BASE = 22,
111
GPS_TYPE_UAVCAN_RTK_ROVER = 23,
112
GPS_TYPE_UNICORE_NMEA = 24,
113
GPS_TYPE_UNICORE_MOVINGBASE_NMEA = 25,
114
GPS_TYPE_SBF_DUAL_ANTENNA = 26,
115
#if HAL_SIM_GPS_ENABLED
116
GPS_TYPE_SITL = 100,
117
#endif
118
};
119
120
// convenience methods for working out what general type an instance is:
121
bool is_rtk_base(uint8_t instance) const;
122
bool is_rtk_rover(uint8_t instance) const;
123
124
// params for an instance:
125
class Params {
126
public:
127
// Constructor
128
Params(void);
129
130
AP_Enum<GPS_Type> type;
131
AP_Int8 gnss_mode;
132
AP_Int16 rate_ms; // this parameter should always be accessed using get_rate_ms()
133
AP_Vector3f antenna_offset;
134
AP_Int16 delay_ms;
135
AP_Int8 com_port;
136
#if HAL_ENABLE_DRONECAN_DRIVERS
137
AP_Int32 node_id;
138
AP_Int32 override_node_id;
139
#endif
140
#if GPS_MOVING_BASELINE
141
MovingBase mb_params;
142
#endif // GPS_MOVING_BASELINE
143
144
static const struct AP_Param::GroupInfo var_info[];
145
};
146
147
/// GPS status codes. These are kept aligned with MAVLink by
148
/// static_assert in AP_GPS.cpp
149
enum GPS_Status {
150
NO_GPS = 0, ///< No GPS connected/detected
151
NO_FIX = 1, ///< Receiving valid GPS messages but no lock
152
GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock
153
GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock
154
GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
155
GPS_OK_FIX_3D_RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float
156
GPS_OK_FIX_3D_RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed
157
};
158
159
// GPS navigation engine settings. Not all GPS receivers support
160
// this
161
enum GPS_Engine_Setting {
162
GPS_ENGINE_NONE = -1,
163
GPS_ENGINE_PORTABLE = 0,
164
GPS_ENGINE_STATIONARY = 2,
165
GPS_ENGINE_PEDESTRIAN = 3,
166
GPS_ENGINE_AUTOMOTIVE = 4,
167
GPS_ENGINE_SEA = 5,
168
GPS_ENGINE_AIRBORNE_1G = 6,
169
GPS_ENGINE_AIRBORNE_2G = 7,
170
GPS_ENGINE_AIRBORNE_4G = 8
171
};
172
173
// role for auto-config
174
enum GPS_Role {
175
GPS_ROLE_NORMAL,
176
GPS_ROLE_MB_BASE,
177
GPS_ROLE_MB_ROVER,
178
};
179
180
// GPS Covariance Types matching ROS2 sensor_msgs/msg/NavSatFix
181
enum class CovarianceType : uint8_t {
182
UNKNOWN = 0, ///< The GPS does not support any accuracy metrics
183
APPROXIMATED = 1, ///< The accuracy is approximated through metrics such as HDOP/VDOP
184
DIAGONAL_KNOWN = 2, ///< The diagonal (east, north, up) components of covariance are reported by the GPS
185
KNOWN = 3, ///< The full covariance array is reported by the GPS
186
};
187
188
/*
189
The GPS_State structure is filled in by the backend driver as it
190
parses each message from the GPS.
191
*/
192
struct GPS_State {
193
uint8_t instance; // the instance number of this GPS
194
195
// all the following fields must all be filled by the backend driver
196
GPS_Status status; ///< driver fix status
197
uint32_t time_week_ms; ///< GPS time (milliseconds from start of GPS week)
198
uint16_t time_week; ///< GPS week number
199
Location location; ///< last fix location
200
float ground_speed; ///< ground speed in m/s
201
float ground_course; ///< ground course in degrees, wrapped 0-360
202
float gps_yaw; ///< GPS derived yaw information, if available (degrees)
203
uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading
204
bool gps_yaw_configured; ///< GPS is configured to provide yaw
205
uint16_t hdop; ///< horizontal dilution of precision, scaled by a factor of 100 (155 means the HDOP value is 1.55)
206
uint16_t vdop; ///< vertical dilution of precision, scaled by a factor of 100 (155 means the VDOP value is 1.55)
207
uint8_t num_sats; ///< Number of visible satellites
208
Vector3f velocity; ///< 3D velocity in m/s, in NED format
209
float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s
210
float horizontal_accuracy; ///< horizontal RMS accuracy estimate in m
211
float vertical_accuracy; ///< vertical RMS accuracy estimate in m
212
float gps_yaw_accuracy; ///< heading accuracy of the GPS in degrees
213
bool have_vertical_velocity; ///< does GPS give vertical velocity? Set to true only once available.
214
bool have_speed_accuracy; ///< does GPS give speed accuracy? Set to true only once available.
215
bool have_horizontal_accuracy; ///< does GPS give horizontal position accuracy? Set to true only once available.
216
bool have_vertical_accuracy; ///< does GPS give vertical position accuracy? Set to true only once available.
217
bool have_gps_yaw; ///< does GPS give yaw? Set to true only once available.
218
bool have_gps_yaw_accuracy; ///< does the GPS give a heading accuracy estimate? Set to true only once available
219
float undulation; //<height that WGS84 is above AMSL at the current location
220
bool have_undulation; ///<do we have a value for the undulation
221
uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
222
bool announced_detection; ///< true once we have announced GPS has been seen to the user
223
uint64_t last_corrected_gps_time_us;///< the system time we got the last corrected GPS timestamp, microseconds
224
bool corrected_timestamp_updated; ///< true if the corrected timestamp has been updated
225
uint32_t lagged_sample_count; ///< number of samples with 50ms more lag than expected
226
227
// all the following fields must only all be filled by RTK capable backend drivers
228
uint32_t rtk_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
229
uint16_t rtk_week_number; ///< GPS Week Number of last baseline
230
uint32_t rtk_age_ms; ///< GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates overflow)
231
uint8_t rtk_num_sats; ///< Current number of satellites used for RTK calculation
232
uint8_t rtk_baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
233
int32_t rtk_baseline_x_mm; ///< Current baseline in ECEF x or NED north component in mm
234
int32_t rtk_baseline_y_mm; ///< Current baseline in ECEF y or NED east component in mm
235
int32_t rtk_baseline_z_mm; ///< Current baseline in ECEF z or NED down component in mm
236
uint32_t rtk_accuracy; ///< Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
237
int32_t rtk_iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses
238
239
// UBX Relative Position and Heading message information
240
float relPosHeading; ///< Reported Heading in degrees
241
float relPosLength; ///< Reported Position horizontal distance in meters
242
float relPosD; ///< Reported Vertical distance in meters
243
float accHeading; ///< Reported Heading Accuracy in degrees
244
uint32_t relposheading_ts; ///< True if new data has been received since last time it was false
245
};
246
247
/// Startup initialisation.
248
void init();
249
250
// ethod for APPPeriph to set the default type for the first GPS instance:
251
void set_default_type_for_gps1(uint8_t default_type) {
252
params[0].type.set_default(default_type);
253
}
254
255
/// Update GPS state based on possible bytes received from the module.
256
/// This routine must be called periodically (typically at 10Hz or
257
/// more) to process incoming data.
258
void update(void);
259
260
// Pass mavlink data to message handlers (for MAV type)
261
void handle_msg(mavlink_channel_t chan, const mavlink_message_t &msg);
262
#if HAL_MSP_GPS_ENABLED
263
void handle_msp(const MSP::msp_gps_data_message_t &pkt);
264
#endif
265
#if HAL_EXTERNAL_AHRS_ENABLED
266
// Retrieve the first instance ID that is configured as type GPS_TYPE_EXTERNAL_AHRS.
267
// Can be used by external AHRS systems that only report one GPS to get the instance ID.
268
// Returns true if an instance was found, false otherwise.
269
bool get_first_external_instance(uint8_t& instance) const WARN_IF_UNUSED;
270
void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance);
271
#endif
272
273
// Accessor functions
274
275
// return number of active GPS sensors. Note that if the first GPS
276
// is not present but the 2nd is then we return 2. Note that a blended
277
// GPS solution is treated as an additional sensor.
278
uint8_t num_sensors(void) const;
279
280
// Return the index of the primary sensor which is the index of the sensor contributing to
281
// the output. A blended solution is available as an additional instance
282
uint8_t primary_sensor(void) const {
283
return primary_instance;
284
}
285
286
/// Query GPS status
287
GPS_Status status(uint8_t instance) const {
288
if (_force_disable_gps && state[instance].status > NO_FIX) {
289
return NO_FIX;
290
}
291
return state[instance].status;
292
}
293
GPS_Status status(void) const {
294
return status(primary_instance);
295
}
296
297
// return a single human-presentable character representing the
298
// fix type. For space-constrained human-readable displays
299
char status_onechar(void) const {
300
switch (status()) {
301
case AP_GPS::NO_GPS:
302
return ' ';
303
case AP_GPS::NO_FIX:
304
return '-';
305
case AP_GPS::GPS_OK_FIX_2D:
306
return '2';
307
case AP_GPS::GPS_OK_FIX_3D:
308
return '3';
309
case AP_GPS::GPS_OK_FIX_3D_DGPS:
310
return '4';
311
case AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT:
312
return '5';
313
case AP_GPS::GPS_OK_FIX_3D_RTK_FIXED:
314
return '6';
315
}
316
// should never reach here; compiler flags guarantees this.
317
return '?';
318
}
319
320
// Query the highest status this GPS supports (always reports GPS_OK_FIX_3D for the blended GPS)
321
GPS_Status highest_supported_status(uint8_t instance) const WARN_IF_UNUSED;
322
323
// location of last fix
324
const Location &location(uint8_t instance) const {
325
return state[instance].location;
326
}
327
const Location &location() const {
328
return location(primary_instance);
329
}
330
331
// get the difference between WGS84 and AMSL. A positive value means
332
// the AMSL height is higher than WGS84 ellipsoid height
333
bool get_undulation(uint8_t instance, float &undulation) const;
334
335
// get the difference between WGS84 and AMSL. A positive value means
336
// the AMSL height is higher than WGS84 ellipsoid height
337
bool get_undulation(float &undulation) const {
338
return get_undulation(primary_instance, undulation);
339
}
340
341
// report speed accuracy
342
bool speed_accuracy(uint8_t instance, float &sacc) const;
343
bool speed_accuracy(float &sacc) const {
344
return speed_accuracy(primary_instance, sacc);
345
}
346
347
bool horizontal_accuracy(uint8_t instance, float &hacc) const;
348
bool horizontal_accuracy(float &hacc) const {
349
return horizontal_accuracy(primary_instance, hacc);
350
}
351
352
bool vertical_accuracy(uint8_t instance, float &vacc) const;
353
bool vertical_accuracy(float &vacc) const {
354
return vertical_accuracy(primary_instance, vacc);
355
}
356
357
CovarianceType position_covariance(const uint8_t instance, Matrix3f& cov) const WARN_IF_UNUSED;
358
359
// 3D velocity in NED format
360
const Vector3f &velocity(uint8_t instance) const {
361
return state[instance].velocity;
362
}
363
const Vector3f &velocity() const {
364
return velocity(primary_instance);
365
}
366
367
// ground speed in m/s
368
float ground_speed(uint8_t instance) const {
369
return state[instance].ground_speed;
370
}
371
float ground_speed() const {
372
return ground_speed(primary_instance);
373
}
374
375
// ground speed in cm/s
376
uint32_t ground_speed_cm(void) const {
377
return ground_speed() * 100;
378
}
379
380
// ground course in degrees
381
float ground_course(uint8_t instance) const {
382
return state[instance].ground_course;
383
}
384
float ground_course() const {
385
return ground_course(primary_instance);
386
}
387
// ground course in centi-degrees
388
int32_t ground_course_cd(uint8_t instance) const {
389
return ground_course(instance) * 100;
390
}
391
int32_t ground_course_cd() const {
392
return ground_course_cd(primary_instance);
393
}
394
395
// yaw in degrees if available
396
bool gps_yaw_deg(uint8_t instance, float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const;
397
bool gps_yaw_deg(float &yaw_deg, float &accuracy_deg, uint32_t &time_ms) const {
398
return gps_yaw_deg(primary_instance, yaw_deg, accuracy_deg, time_ms);
399
}
400
401
// number of locked satellites
402
uint8_t num_sats(uint8_t instance) const {
403
return state[instance].num_sats;
404
}
405
uint8_t num_sats() const {
406
return num_sats(primary_instance);
407
}
408
409
// GPS time of week in milliseconds
410
uint32_t time_week_ms(uint8_t instance) const {
411
return state[instance].time_week_ms;
412
}
413
uint32_t time_week_ms() const {
414
return time_week_ms(primary_instance);
415
}
416
417
// GPS week
418
uint16_t time_week(uint8_t instance) const {
419
return state[instance].time_week;
420
}
421
uint16_t time_week() const {
422
return time_week(primary_instance);
423
}
424
425
// horizontal dilution of precision
426
uint16_t get_hdop(uint8_t instance) const {
427
return state[instance].hdop;
428
}
429
uint16_t get_hdop() const {
430
return get_hdop(primary_instance);
431
}
432
433
// vertical dilution of precision
434
uint16_t get_vdop(uint8_t instance) const {
435
return state[instance].vdop;
436
}
437
uint16_t get_vdop() const {
438
return get_vdop(primary_instance);
439
}
440
441
// the time we got our last fix in system milliseconds. This is
442
// used when calculating how far we might have moved since that fix
443
uint32_t last_fix_time_ms(uint8_t instance) const {
444
return timing[instance].last_fix_time_ms;
445
}
446
uint32_t last_fix_time_ms(void) const {
447
return last_fix_time_ms(primary_instance);
448
}
449
450
// the time we last processed a message in milliseconds. This is
451
// used to indicate that we have new GPS data to process
452
uint32_t last_message_time_ms(uint8_t instance) const {
453
return timing[instance].last_message_time_ms;
454
}
455
uint32_t last_message_time_ms(void) const {
456
return last_message_time_ms(primary_instance);
457
}
458
459
// system time delta between the last two reported positions
460
uint16_t last_message_delta_time_ms(uint8_t instance) const {
461
return timing[instance].delta_time_ms;
462
}
463
uint16_t last_message_delta_time_ms(void) const {
464
return last_message_delta_time_ms(primary_instance);
465
}
466
467
// return true if the GPS supports vertical velocity values
468
bool have_vertical_velocity(uint8_t instance) const {
469
return state[instance].have_vertical_velocity;
470
}
471
bool have_vertical_velocity(void) const {
472
return have_vertical_velocity(primary_instance);
473
}
474
475
// return true if the GPS currently has yaw available
476
bool have_gps_yaw(uint8_t instance) const {
477
return !_force_disable_gps_yaw && state[instance].have_gps_yaw;
478
}
479
bool have_gps_yaw(void) const {
480
return have_gps_yaw(primary_instance);
481
}
482
483
// return true if the GPS is configured to provide yaw. This will
484
// be true if we expect the GPS to provide yaw, even if it
485
// currently is not able to provide yaw
486
bool have_gps_yaw_configured(uint8_t instance) const {
487
return state[instance].gps_yaw_configured;
488
}
489
490
// the expected lag (in seconds) in the position and velocity readings from the gps
491
// return true if the GPS hardware configuration is known or the lag parameter has been set manually
492
bool get_lag(uint8_t instance, float &lag_sec) const;
493
bool get_lag(float &lag_sec) const {
494
return get_lag(primary_instance, lag_sec);
495
}
496
497
// return a 3D vector defining the offset of the GPS antenna in meters relative to the body frame origin
498
const Vector3f &get_antenna_offset(uint8_t instance) const;
499
500
// lock out a GPS port, allowing another application to use the port
501
void lock_port(uint8_t instance, bool locked);
502
503
//MAVLink Status Sending
504
void send_mavlink_gps_raw(mavlink_channel_t chan);
505
void send_mavlink_gps2_raw(mavlink_channel_t chan);
506
507
void send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst);
508
509
// Returns true if there is an unconfigured GPS, and provides the instance number of the first non configured GPS
510
bool first_unconfigured_gps(uint8_t &instance) const WARN_IF_UNUSED;
511
void broadcast_first_configuration_failure_reason(void) const;
512
513
// pre-arm check that all GPSs are close to each other. farthest distance between GPSs (in meters) is returned
514
bool all_consistent(float &distance) const;
515
516
// handle sending of initialisation strings to the GPS - only used by backends
517
void send_blob_start(uint8_t instance);
518
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
519
void send_blob_update(uint8_t instance);
520
521
// return last fix time since the 1/1/1970 in microseconds
522
uint64_t time_epoch_usec(uint8_t instance) const;
523
uint64_t time_epoch_usec(void) const {
524
return time_epoch_usec(primary_instance);
525
}
526
527
uint64_t last_message_epoch_usec(uint8_t instance) const;
528
uint64_t last_message_epoch_usec() const {
529
return last_message_epoch_usec(primary_instance);
530
}
531
532
// convert GPS week and millis to unix epoch in ms
533
static uint64_t istate_time_to_epoch_ms(uint16_t gps_week, uint32_t gps_ms);
534
535
static const struct AP_Param::GroupInfo var_info[];
536
537
#if HAL_LOGGING_ENABLED
538
void Write_AP_Logger_Log_Startup_messages();
539
#endif
540
541
// indicate which bit in LOG_BITMASK indicates gps logging enabled
542
void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }
543
544
// report if the gps is healthy (this is defined as existing, an update at a rate greater than 4Hz,
545
// as well as any driver specific behaviour)
546
bool is_healthy(uint8_t instance) const;
547
bool is_healthy(void) const { return is_healthy(primary_instance); }
548
549
// returns true if all GPS instances have passed all final arming checks/state changes
550
bool prepare_for_arming(void);
551
552
// returns true if all GPS backend drivers are OK with the concept
553
// of the vehicle arming. this is for backends to be able to
554
// spout pre arm error messages
555
bool pre_arm_checks(char failure_msg[], uint16_t failure_msg_len);
556
557
// returns false if any GPS drivers are not performing their logging appropriately
558
bool logging_failed(void) const;
559
560
bool logging_present(void) const { return _raw_data != 0; }
561
bool logging_enabled(void) const { return _raw_data != 0; }
562
563
// used to disable GPS for GPS failure testing in flight
564
void force_disable(bool disable) {
565
_force_disable_gps = disable;
566
}
567
568
// used to disable GPS yaw for GPS failure testing in flight
569
void set_force_disable_yaw(bool disable) {
570
_force_disable_gps_yaw = disable;
571
}
572
573
// handle possibly fragmented RTCM injection data
574
void handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_t len);
575
576
// get configured type by instance
577
GPS_Type get_type(uint8_t instance) const {
578
return instance>=ARRAY_SIZE(params) ? GPS_Type::GPS_TYPE_NONE : params[instance].type;
579
}
580
581
// get iTOW, if supported, zero otherwie
582
uint32_t get_itow(uint8_t instance) const;
583
584
bool get_error_codes(uint8_t instance, uint32_t &error_codes) const;
585
bool get_error_codes(uint32_t &error_codes) const { return get_error_codes(primary_instance, error_codes); }
586
587
enum class SBAS_Mode : int8_t {
588
Disabled = 0,
589
Enabled = 1,
590
DoNotChange = 2,
591
};
592
593
#if GPS_MOVING_BASELINE
594
// methods used by UAVCAN GPS driver and AP_Periph for moving baseline
595
void inject_MBL_data(uint8_t* data, uint16_t length);
596
bool get_RelPosHeading(uint32_t &timestamp, float &relPosHeading, float &relPosLength, float &relPosD, float &accHeading) WARN_IF_UNUSED;
597
bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len);
598
void clear_RTCMV3();
599
#endif // GPS_MOVING_BASELINE
600
601
#if !AP_GPS_BLENDED_ENABLED
602
uint8_t get_auto_switch_type() const { return _auto_switch; }
603
#endif
604
605
protected:
606
607
// configuration parameters
608
Params params[GPS_MAX_INSTANCES];
609
AP_Int8 _navfilter;
610
AP_Int8 _auto_switch;
611
AP_Int16 _sbp_logmask;
612
AP_Int8 _inject_to;
613
uint32_t _last_instance_swap_ms;
614
AP_Enum<SBAS_Mode> _sbas_mode;
615
AP_Int8 _min_elevation;
616
AP_Int8 _raw_data;
617
AP_Int8 _save_config;
618
AP_Int8 _auto_config;
619
AP_Int8 _blend_mask;
620
AP_Int16 _driver_options;
621
AP_Int8 _primary;
622
623
uint32_t _log_gps_bit = -1;
624
625
enum DriverOptions : int16_t {
626
UBX_MBUseUart2 = (1U << 0U),
627
SBF_UseBaseForYaw = (1U << 1U),
628
UBX_Use115200 = (1U << 2U),
629
UAVCAN_MBUseDedicatedBus = (1 << 3U),
630
HeightEllipsoid = (1U << 4),
631
GPSL5HealthOverride = (1U << 5),
632
AlwaysRTCMDecode = (1U << 6),
633
DisableRTCMDecode = (1U << 7),
634
};
635
636
// check if an option is set
637
bool option_set(const DriverOptions option) const {
638
return (uint8_t(_driver_options.get()) & uint8_t(option)) != 0;
639
}
640
641
private:
642
static AP_GPS *_singleton;
643
HAL_Semaphore rsem;
644
645
// returns the desired gps update rate in milliseconds
646
// this does not provide any guarantee that the GPS is updating at the requested
647
// rate it is simply a helper for use in the backends for determining what rate
648
// they should be configuring the GPS to run at
649
uint16_t get_rate_ms(uint8_t instance) const;
650
651
struct GPS_timing {
652
// the time we got our last fix in system milliseconds
653
uint32_t last_fix_time_ms;
654
655
// the time we got our last message in system milliseconds
656
uint32_t last_message_time_ms;
657
658
// delta time between the last pair of GPS updates in system milliseconds
659
uint16_t delta_time_ms;
660
661
// count of delayed frames
662
uint8_t delayed_count;
663
664
// the average time delta
665
float average_delta_ms;
666
};
667
// Note allowance for an additional instance to contain blended data
668
GPS_timing timing[GPS_MAX_INSTANCES];
669
GPS_State state[GPS_MAX_INSTANCES];
670
AP_GPS_Backend *drivers[GPS_MAX_INSTANCES];
671
AP_HAL::UARTDriver *_port[GPS_MAX_RECEIVERS];
672
673
/// primary GPS instance
674
uint8_t primary_instance;
675
676
/// number of GPS instances present
677
uint8_t num_instances;
678
679
// which ports are locked
680
uint8_t locked_ports;
681
682
// state of auto-detection process, per instance
683
struct detect_state {
684
uint32_t last_baud_change_ms;
685
uint8_t current_baud;
686
uint32_t probe_baud;
687
bool auto_detected_baud;
688
#if AP_GPS_UBLOX_ENABLED
689
struct UBLOX_detect_state ublox_detect_state;
690
#endif
691
#if AP_GPS_SIRF_ENABLED
692
struct SIRF_detect_state sirf_detect_state;
693
#endif
694
#if AP_GPS_NMEA_ENABLED
695
struct NMEA_detect_state nmea_detect_state;
696
#endif
697
#if AP_GPS_SBP_ENABLED
698
struct SBP_detect_state sbp_detect_state;
699
#endif
700
#if AP_GPS_SBP2_ENABLED
701
struct SBP2_detect_state sbp2_detect_state;
702
#endif
703
#if AP_GPS_ERB_ENABLED
704
struct ERB_detect_state erb_detect_state;
705
#endif
706
} detect_state[GPS_MAX_RECEIVERS];
707
708
struct {
709
const char *blob;
710
uint16_t remaining;
711
} initblob_state[GPS_MAX_RECEIVERS];
712
713
static const uint32_t _baudrates[];
714
static const char _initialisation_blob[];
715
static const char _initialisation_raw_blob[];
716
717
void detect_instance(uint8_t instance);
718
// run detection step for one GPS instance. If this finds a GPS then it
719
// will return it - otherwise nullptr
720
AP_GPS_Backend *_detect_instance(uint8_t instance);
721
722
void update_instance(uint8_t instance);
723
724
/*
725
buffer for re-assembling RTCM data for GPS injection.
726
The 8 bit flags field in GPS_RTCM_DATA is interpreted as:
727
1 bit for "is fragmented"
728
2 bits for fragment number
729
5 bits for sequence number
730
731
The rtcm_buffer is allocated on first use. Once a block of data
732
is successfully reassembled it is injected into all active GPS
733
backends. This assumes we don't want more than 4*180=720 bytes
734
in a RTCM data block
735
*/
736
struct rtcm_buffer {
737
uint8_t fragments_received;
738
uint8_t sequence;
739
uint8_t fragment_count;
740
uint16_t total_length;
741
uint8_t buffer[MAVLINK_MSG_GPS_RTCM_DATA_FIELD_DATA_LEN*4];
742
} *rtcm_buffer;
743
744
struct {
745
uint16_t fragments_used;
746
uint16_t fragments_discarded;
747
} rtcm_stats;
748
749
// re-assemble GPS_RTCM_DATA message
750
void handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_t &msg);
751
void handle_gps_inject(const mavlink_message_t &msg);
752
753
//Inject a packet of raw binary to a GPS
754
void inject_data(const uint8_t *data, uint16_t len);
755
void inject_data(uint8_t instance, const uint8_t *data, uint16_t len);
756
757
#if AP_GPS_BLENDED_ENABLED
758
bool _output_is_blended; // true when a blended GPS solution being output
759
#endif
760
761
bool should_log() const;
762
763
bool needs_uart(GPS_Type type) const;
764
765
#if GPS_MAX_RECEIVERS > 1
766
/// Update primary instance
767
void update_primary(void);
768
#endif
769
770
// helper function for mavlink gps yaw
771
uint16_t gps_yaw_cdeg(uint8_t instance) const;
772
773
// Auto configure types
774
enum GPS_AUTO_CONFIG {
775
GPS_AUTO_CONFIG_DISABLE = 0,
776
GPS_AUTO_CONFIG_ENABLE_SERIAL_ONLY = 1,
777
GPS_AUTO_CONFIG_ENABLE_ALL = 2,
778
};
779
780
enum class GPSAutoSwitch {
781
NONE = 0,
782
USE_BEST = 1,
783
BLEND = 2,
784
//USE_SECOND = 3, deprecated for new primary param
785
USE_PRIMARY_IF_3D_FIX = 4,
786
};
787
788
// used for flight testing with GPS loss
789
bool _force_disable_gps;
790
791
// used for flight testing with GPS yaw loss
792
bool _force_disable_gps_yaw;
793
794
// logging support
795
void Write_GPS(uint8_t instance);
796
797
#if AP_GPS_RTCM_DECODE_ENABLED
798
/*
799
per mavlink channel RTCM decoder, enabled with RTCM decode
800
option in GPS_DRV_OPTIONS
801
*/
802
struct {
803
RTCM3_Parser *parsers[MAVLINK_COMM_NUM_BUFFERS];
804
uint32_t sent_crc[32];
805
uint8_t sent_idx;
806
uint16_t seen_mav_channels;
807
} rtcm;
808
bool parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt);
809
#endif
810
811
void convert_parameters();
812
};
813
814
namespace AP {
815
AP_GPS &gps();
816
};
817
818
#endif // AP_GPS_ENABLED
819
820