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_Blended.cpp
Views: 1798
1
#include "AP_GPS_config.h"
2
3
#if AP_GPS_BLENDED_ENABLED
4
5
#include "AP_GPS_Blended.h"
6
7
// defines used to specify the mask position for use of different accuracy metrics in the blending algorithm
8
#define BLEND_MASK_USE_HPOS_ACC 1
9
#define BLEND_MASK_USE_VPOS_ACC 2
10
#define BLEND_MASK_USE_SPD_ACC 4
11
12
#define BLEND_COUNTER_FAILURE_INCREMENT 10
13
14
/*
15
calculate the weightings used to blend GPSs location and velocity data
16
*/
17
bool AP_GPS_Blended::_calc_weights(void)
18
{
19
// zero the blend weights
20
memset(&_blend_weights, 0, sizeof(_blend_weights));
21
22
23
static_assert(GPS_MAX_RECEIVERS == 2, "GPS blending only currently works with 2 receivers");
24
// Note that the early quit below relies upon exactly 2 instances
25
// The time delta calculations below also rely upon every instance being currently detected and being parsed
26
27
// exit immediately if not enough receivers to do blending
28
if (gps.state[0].status <= AP_GPS::NO_FIX || gps.state[1].status <= AP_GPS::NO_FIX) {
29
return false;
30
}
31
32
// Use the oldest non-zero time, but if time difference is excessive, use newest to prevent a disconnected receiver from blocking updates
33
uint32_t max_ms = 0; // newest non-zero system time of arrival of a GPS message
34
uint32_t min_ms = -1; // oldest non-zero system time of arrival of a GPS message
35
uint32_t max_rate_ms = 0; // largest update interval of a GPS receiver
36
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
37
// Find largest and smallest times
38
if (gps.state[i].last_gps_time_ms > max_ms) {
39
max_ms = gps.state[i].last_gps_time_ms;
40
}
41
if ((gps.state[i].last_gps_time_ms < min_ms) && (gps.state[i].last_gps_time_ms > 0)) {
42
min_ms = gps.state[i].last_gps_time_ms;
43
}
44
max_rate_ms = MAX(gps.get_rate_ms(i), max_rate_ms);
45
if (isinf(gps.state[i].speed_accuracy) ||
46
isinf(gps.state[i].horizontal_accuracy) ||
47
isinf(gps.state[i].vertical_accuracy)) {
48
return false;
49
}
50
}
51
if ((max_ms - min_ms) < (2 * max_rate_ms)) {
52
// data is not too delayed so use the oldest time_stamp to give a chance for data from that receiver to be updated
53
state.last_gps_time_ms = min_ms;
54
} else {
55
// receiver data has timed out so fail out of blending
56
return false;
57
}
58
59
// calculate the sum squared speed accuracy across all GPS sensors
60
float speed_accuracy_sum_sq = 0.0f;
61
if (gps._blend_mask & BLEND_MASK_USE_SPD_ACC) {
62
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
63
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {
64
if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f) {
65
speed_accuracy_sum_sq += sq(gps.state[i].speed_accuracy);
66
} else {
67
// not all receivers support this metric so set it to zero and don't use it
68
speed_accuracy_sum_sq = 0.0f;
69
break;
70
}
71
}
72
}
73
}
74
75
// calculate the sum squared horizontal position accuracy across all GPS sensors
76
float horizontal_accuracy_sum_sq = 0.0f;
77
if (gps._blend_mask & BLEND_MASK_USE_HPOS_ACC) {
78
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
79
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D) {
80
if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f) {
81
horizontal_accuracy_sum_sq += sq(gps.state[i].horizontal_accuracy);
82
} else {
83
// not all receivers support this metric so set it to zero and don't use it
84
horizontal_accuracy_sum_sq = 0.0f;
85
break;
86
}
87
}
88
}
89
}
90
91
// calculate the sum squared vertical position accuracy across all GPS sensors
92
float vertical_accuracy_sum_sq = 0.0f;
93
if (gps._blend_mask & BLEND_MASK_USE_VPOS_ACC) {
94
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
95
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D) {
96
if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f) {
97
vertical_accuracy_sum_sq += sq(gps.state[i].vertical_accuracy);
98
} else {
99
// not all receivers support this metric so set it to zero and don't use it
100
vertical_accuracy_sum_sq = 0.0f;
101
break;
102
}
103
}
104
}
105
}
106
// Check if we can do blending using reported accuracy
107
bool can_do_blending = (horizontal_accuracy_sum_sq > 0.0f || vertical_accuracy_sum_sq > 0.0f || speed_accuracy_sum_sq > 0.0f);
108
109
// if we can't do blending using reported accuracy, return false and hard switch logic will be used instead
110
if (!can_do_blending) {
111
return false;
112
}
113
114
float sum_of_all_weights = 0.0f;
115
116
// calculate a weighting using the reported horizontal position
117
float hpos_blend_weights[GPS_MAX_RECEIVERS] = {};
118
if (horizontal_accuracy_sum_sq > 0.0f) {
119
// calculate the weights using the inverse of the variances
120
float sum_of_hpos_weights = 0.0f;
121
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
122
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_2D && gps.state[i].horizontal_accuracy >= 0.001f) {
123
hpos_blend_weights[i] = horizontal_accuracy_sum_sq / sq(gps.state[i].horizontal_accuracy);
124
sum_of_hpos_weights += hpos_blend_weights[i];
125
}
126
}
127
// normalise the weights
128
if (sum_of_hpos_weights > 0.0f) {
129
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
130
hpos_blend_weights[i] = hpos_blend_weights[i] / sum_of_hpos_weights;
131
}
132
sum_of_all_weights += 1.0f;
133
}
134
}
135
136
// calculate a weighting using the reported vertical position accuracy
137
float vpos_blend_weights[GPS_MAX_RECEIVERS] = {};
138
if (vertical_accuracy_sum_sq > 0.0f) {
139
// calculate the weights using the inverse of the variances
140
float sum_of_vpos_weights = 0.0f;
141
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
142
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].vertical_accuracy >= 0.001f) {
143
vpos_blend_weights[i] = vertical_accuracy_sum_sq / sq(gps.state[i].vertical_accuracy);
144
sum_of_vpos_weights += vpos_blend_weights[i];
145
}
146
}
147
// normalise the weights
148
if (sum_of_vpos_weights > 0.0f) {
149
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
150
vpos_blend_weights[i] = vpos_blend_weights[i] / sum_of_vpos_weights;
151
}
152
sum_of_all_weights += 1.0f;
153
};
154
}
155
156
// calculate a weighting using the reported speed accuracy
157
float spd_blend_weights[GPS_MAX_RECEIVERS] = {};
158
if (speed_accuracy_sum_sq > 0.0f) {
159
// calculate the weights using the inverse of the variances
160
float sum_of_spd_weights = 0.0f;
161
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
162
if (gps.state[i].status >= AP_GPS::GPS_OK_FIX_3D && gps.state[i].speed_accuracy >= 0.001f) {
163
spd_blend_weights[i] = speed_accuracy_sum_sq / sq(gps.state[i].speed_accuracy);
164
sum_of_spd_weights += spd_blend_weights[i];
165
}
166
}
167
// normalise the weights
168
if (sum_of_spd_weights > 0.0f) {
169
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
170
spd_blend_weights[i] = spd_blend_weights[i] / sum_of_spd_weights;
171
}
172
sum_of_all_weights += 1.0f;
173
}
174
}
175
176
if (!is_positive(sum_of_all_weights)) {
177
return false;
178
}
179
180
// calculate an overall weight
181
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
182
_blend_weights[i] = (hpos_blend_weights[i] + vpos_blend_weights[i] + spd_blend_weights[i]) / sum_of_all_weights;
183
}
184
185
return true;
186
}
187
188
bool AP_GPS_Blended::calc_weights()
189
{
190
// adjust blend health counter
191
if (!_calc_weights()) {
192
_blend_health_counter = MIN(_blend_health_counter+BLEND_COUNTER_FAILURE_INCREMENT, 100);
193
} else if (_blend_health_counter > 0) {
194
_blend_health_counter--;
195
}
196
// stop blending if unhealthy
197
return _blend_health_counter < 50;
198
}
199
200
/*
201
calculate a blended GPS state
202
*/
203
void AP_GPS_Blended::calc_state(void)
204
{
205
// initialise the blended states so we can accumulate the results using the weightings for each GPS receiver
206
state.instance = GPS_BLENDED_INSTANCE;
207
state.status = AP_GPS::NO_FIX;
208
state.time_week_ms = 0;
209
state.time_week = 0;
210
state.ground_speed = 0.0f;
211
state.ground_course = 0.0f;
212
state.hdop = GPS_UNKNOWN_DOP;
213
state.vdop = GPS_UNKNOWN_DOP;
214
state.num_sats = 0;
215
state.velocity.zero();
216
state.speed_accuracy = 1e6f;
217
state.horizontal_accuracy = 1e6f;
218
state.vertical_accuracy = 1e6f;
219
state.have_vertical_velocity = false;
220
state.have_speed_accuracy = false;
221
state.have_horizontal_accuracy = false;
222
state.have_vertical_accuracy = false;
223
state.location = {};
224
225
_blended_antenna_offset.zero();
226
_blended_lag_sec = 0;
227
228
#if HAL_LOGGING_ENABLED
229
const uint32_t last_blended_message_time_ms = timing.last_message_time_ms;
230
#endif
231
timing.last_fix_time_ms = 0;
232
timing.last_message_time_ms = 0;
233
234
if (gps.state[0].have_undulation) {
235
state.have_undulation = true;
236
state.undulation = gps.state[0].undulation;
237
} else if (gps.state[1].have_undulation) {
238
state.have_undulation = true;
239
state.undulation = gps.state[1].undulation;
240
} else {
241
state.have_undulation = false;
242
}
243
244
// combine the states into a blended solution
245
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
246
// use the highest status
247
if (gps.state[i].status > state.status) {
248
state.status = gps.state[i].status;
249
}
250
251
// calculate a blended average velocity
252
state.velocity += gps.state[i].velocity * _blend_weights[i];
253
254
// report the best valid accuracies and DOP metrics
255
256
if (gps.state[i].have_horizontal_accuracy && gps.state[i].horizontal_accuracy > 0.0f && gps.state[i].horizontal_accuracy < state.horizontal_accuracy) {
257
state.have_horizontal_accuracy = true;
258
state.horizontal_accuracy = gps.state[i].horizontal_accuracy;
259
}
260
261
if (gps.state[i].have_vertical_accuracy && gps.state[i].vertical_accuracy > 0.0f && gps.state[i].vertical_accuracy < state.vertical_accuracy) {
262
state.have_vertical_accuracy = true;
263
state.vertical_accuracy = gps.state[i].vertical_accuracy;
264
}
265
266
if (gps.state[i].have_vertical_velocity) {
267
state.have_vertical_velocity = true;
268
}
269
270
if (gps.state[i].have_speed_accuracy && gps.state[i].speed_accuracy > 0.0f && gps.state[i].speed_accuracy < state.speed_accuracy) {
271
state.have_speed_accuracy = true;
272
state.speed_accuracy = gps.state[i].speed_accuracy;
273
}
274
275
if (gps.state[i].hdop > 0 && gps.state[i].hdop < state.hdop) {
276
state.hdop = gps.state[i].hdop;
277
}
278
279
if (gps.state[i].vdop > 0 && gps.state[i].vdop < state.vdop) {
280
state.vdop = gps.state[i].vdop;
281
}
282
283
if (gps.state[i].num_sats > 0 && gps.state[i].num_sats > state.num_sats) {
284
state.num_sats = gps.state[i].num_sats;
285
}
286
287
// report a blended average GPS antenna position
288
Vector3f temp_antenna_offset = gps.params[i].antenna_offset;
289
temp_antenna_offset *= _blend_weights[i];
290
_blended_antenna_offset += temp_antenna_offset;
291
292
// blend the timing data
293
if (gps.timing[i].last_fix_time_ms > timing.last_fix_time_ms) {
294
timing.last_fix_time_ms = gps.timing[i].last_fix_time_ms;
295
}
296
if (gps.timing[i].last_message_time_ms > timing.last_message_time_ms) {
297
timing.last_message_time_ms = gps.timing[i].last_message_time_ms;
298
}
299
}
300
301
/*
302
* Calculate an instantaneous weighted/blended average location from the available GPS instances and store in the _output_state.
303
* This will be statistically the most likely location, but will be not stable enough for direct use by the autopilot.
304
*/
305
306
// Use the GPS with the highest weighting as the reference position
307
float best_weight = 0.0f;
308
uint8_t best_index = 0;
309
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
310
if (_blend_weights[i] > best_weight) {
311
best_weight = _blend_weights[i];
312
best_index = i;
313
state.location = gps.state[i].location;
314
}
315
}
316
317
// Calculate the weighted sum of horizontal and vertical position offsets relative to the reference position
318
Vector2f blended_NE_offset_m;
319
float blended_alt_offset_cm = 0.0f;
320
blended_NE_offset_m.zero();
321
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
322
if (_blend_weights[i] > 0.0f && i != best_index) {
323
blended_NE_offset_m += state.location.get_distance_NE(gps.state[i].location) * _blend_weights[i];
324
blended_alt_offset_cm += (float)(gps.state[i].location.alt - state.location.alt) * _blend_weights[i];
325
}
326
}
327
328
// Add the sum of weighted offsets to the reference location to obtain the blended location
329
state.location.offset(blended_NE_offset_m.x, blended_NE_offset_m.y);
330
state.location.alt += (int)blended_alt_offset_cm;
331
332
// Calculate ground speed and course from blended velocity vector
333
state.ground_speed = state.velocity.xy().length();
334
state.ground_course = wrap_360(degrees(atan2f(state.velocity.y, state.velocity.x)));
335
336
// If the GPS week is the same then use a blended time_week_ms
337
// If week is different, then use time stamp from GPS with largest weighting
338
// detect inconsistent week data
339
uint8_t last_week_instance = 0;
340
bool weeks_consistent = true;
341
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
342
if (last_week_instance == 0 && _blend_weights[i] > 0) {
343
// this is our first valid sensor week data
344
last_week_instance = gps.state[i].time_week;
345
} else if (last_week_instance != 0 && _blend_weights[i] > 0 && last_week_instance != gps.state[i].time_week) {
346
// there is valid sensor week data that is inconsistent
347
weeks_consistent = false;
348
}
349
}
350
// calculate output
351
if (!weeks_consistent) {
352
// use data from highest weighted sensor
353
state.time_week = gps.state[best_index].time_week;
354
state.time_week_ms = gps.state[best_index].time_week_ms;
355
} else {
356
// use week number from highest weighting GPS (they should all have the same week number)
357
state.time_week = gps.state[best_index].time_week;
358
// calculate a blended value for the number of ms lapsed in the week
359
double temp_time_0 = 0.0;
360
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
361
if (_blend_weights[i] > 0.0f) {
362
temp_time_0 += (double)gps.state[i].time_week_ms * (double)_blend_weights[i];
363
}
364
}
365
state.time_week_ms = (uint32_t)temp_time_0;
366
}
367
368
// calculate a blended value for the timing data and lag
369
double temp_time_1 = 0.0;
370
double temp_time_2 = 0.0;
371
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
372
if (_blend_weights[i] > 0.0f) {
373
temp_time_1 += (double)gps.timing[i].last_fix_time_ms * (double) _blend_weights[i];
374
temp_time_2 += (double)gps.timing[i].last_message_time_ms * (double)_blend_weights[i];
375
float gps_lag_sec = 0;
376
gps.get_lag(i, gps_lag_sec);
377
_blended_lag_sec += gps_lag_sec * _blend_weights[i];
378
}
379
}
380
timing.last_fix_time_ms = (uint32_t)temp_time_1;
381
timing.last_message_time_ms = (uint32_t)temp_time_2;
382
383
#if HAL_LOGGING_ENABLED
384
if (timing.last_message_time_ms > last_blended_message_time_ms &&
385
should_log()) {
386
gps.Write_GPS(GPS_BLENDED_INSTANCE);
387
}
388
#endif
389
}
390
391
bool AP_GPS_Blended::get_lag(float &lag_sec) const
392
{
393
lag_sec = _blended_lag_sec;
394
// auto switching uses all GPS receivers, so all must be configured
395
uint8_t inst; // we don't actually care what the number is, but must pass it
396
return gps.first_unconfigured_gps(inst);
397
}
398
399
#endif // AP_GPS_BLENDED_ENABLED
400
401