-
Notifications
You must be signed in to change notification settings - Fork 13.6k
/
gps_control.cpp
427 lines (339 loc) · 15.1 KB
/
gps_control.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
/****************************************************************************
*
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file gps_control.cpp
* Control functions for ekf GNSS fusion
*/
#include "ekf.h"
#include <mathlib/mathlib.h>
void Ekf::controlGpsFusion(const imuSample &imu_delayed)
{
if (!_gps_buffer || (_params.gnss_ctrl == 0)) {
stopGpsFusion();
return;
}
_gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL);
// check for arrival of new sensor data at the fusion time horizon
_gps_data_ready = _gps_buffer->pop_first_older_than(imu_delayed.time_us, &_gps_sample_delayed);
if (_gps_data_ready) {
// correct velocity for offset relative to IMU
const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body;
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
_gps_sample_delayed.vel -= vel_offset_earth;
// correct position and height for offset relative to IMU
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
_gps_sample_delayed.pos -= pos_offset_earth.xy();
_gps_sample_delayed.hgt += pos_offset_earth(2);
// update GSF yaw estimator velocity (basic sanity check on GNSS velocity data)
if ((_gps_sample_delayed.sacc > 0.f) && (_gps_sample_delayed.sacc < _params.req_sacc)
&& _gps_sample_delayed.vel.isAllFinite()
) {
_yawEstimator.setVelocity(_gps_sample_delayed.vel.xy(), math::max(_gps_sample_delayed.sacc, _params.gps_vel_noise));
}
}
// run EKF-GSF yaw estimator once per imu_delayed update after all main EKF data samples available
_yawEstimator.update(imu_delayed, _control_status.flags.in_air, getGyroBias());
// Check for new GPS data that has fallen behind the fusion time horizon
if (_gps_data_ready) {
const gpsSample &gps_sample{_gps_sample_delayed};
const bool gps_checks_passing = isTimedOut(_last_gps_fail_us, (uint64_t)5e6);
const bool gps_checks_failing = isTimedOut(_last_gps_pass_us, (uint64_t)5e6);
#if defined(CONFIG_EKF2_GNSS_YAW)
controlGpsYawFusion(gps_sample, gps_checks_passing, gps_checks_failing);
#endif // CONFIG_EKF2_GNSS_YAW
// GNSS velocity
const Vector3f velocity{gps_sample.vel};
const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f));
updateVelocityAidSrcStatus(gps_sample.time_us,
velocity, // observation
vel_obs_var, // observation variance
math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate
_aid_src_gnss_vel);
_aid_src_gnss_vel.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::VEL);
// GNSS position
const Vector2f position{gps_sample.pos};
// relax the upper observation noise limit which prevents bad GPS perturbing the position estimate
float pos_noise = math::max(gps_sample.hacc, _params.gps_pos_noise);
if (!isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
// if we are not using another source of aiding, then we are reliant on the GPS
// observations to constrain attitude errors and must limit the observation noise value.
if (pos_noise > _params.pos_noaid_noise) {
pos_noise = _params.pos_noaid_noise;
}
}
const float pos_var = sq(pos_noise);
const Vector2f pos_obs_var(pos_var, pos_var);
updateHorizontalPositionAidSrcStatus(gps_sample.time_us,
position, // observation
pos_obs_var, // observation variance
math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate
_aid_src_gnss_pos);
_aid_src_gnss_pos.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::HPOS);
// Determine if we should use GPS aiding for velocity and horizontal position
// To start using GPS we need angular alignment completed, the local NED origin set and GPS data that has not failed checks recently
bool mandatory_conditions_passing = false;
if (((_params.gnss_ctrl & GnssCtrl::HPOS) || (_params.gnss_ctrl & GnssCtrl::VEL))
&& _control_status.flags.tilt_align
&& _NED_origin_initialised
) {
// if GPS is otherwise ready to go other than yaw align
if (!_control_status.flags.yaw_align && gps_checks_passing && !gps_checks_failing) {
if (resetYawToEKFGSF()) {
ECL_INFO("GPS yaw aligned using IMU");
}
}
if (_control_status.flags.yaw_align) {
mandatory_conditions_passing = true;
}
}
const bool continuing_conditions_passing = mandatory_conditions_passing && !gps_checks_failing;
const bool starting_conditions_passing = continuing_conditions_passing && gps_checks_passing;
if (_control_status.flags.gps) {
if (mandatory_conditions_passing) {
if (continuing_conditions_passing
|| !isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
fuseVelocity(_aid_src_gnss_vel);
fuseHorizontalPosition(_aid_src_gnss_pos);
bool do_vel_pos_reset = shouldResetGpsFusion();
if (isYawFailure()
&& _control_status.flags.in_air
&& isTimedOut(_time_last_hor_vel_fuse, _params.EKFGSF_reset_delay)
&& (_time_last_hor_vel_fuse > _time_last_on_ground_us)) {
/* A rapid reset to the yaw emergency estimate is performed if horizontal velocity innovation checks continuously
* fails while the difference between the yaw emergency estimator and the yas estimate is large.
* This enables recovery from a bad yaw estimate. A reset is not performed if the fault condition was
* present before flight to prevent triggering due to GPS glitches or other sensor errors.
*/
if (resetYawToEKFGSF()) {
ECL_WARN("GPS emergency yaw reset");
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
// stop using the magnetometer in the main EKF otherwise its fusion could drag the yaw around
// and cause another navigation failure
_control_status.flags.mag_fault = true;
_warning_events.flags.emergency_yaw_reset_mag_stopped = true;
}
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
_control_status.flags.gps_yaw_fault = true;
_warning_events.flags.emergency_yaw_reset_gps_yaw_stopped = true;
}
#endif // CONFIG_EKF2_GNSS_YAW
#if defined(CONFIG_EKF2_EXTERNAL_VISION)
if (_control_status.flags.ev_yaw) {
_control_status.flags.ev_yaw_fault = true;
}
#endif // CONFIG_EKF2_EXTERNAL_VISION
do_vel_pos_reset = true;
}
}
if (do_vel_pos_reset) {
ECL_WARN("GPS fusion timeout, resetting velocity and position");
// reset velocity
_information_events.flags.reset_vel_to_gps = true;
resetVelocityTo(velocity, vel_obs_var);
_aid_src_gnss_vel.time_last_fuse = _time_delayed_us;
// reset position
_information_events.flags.reset_pos_to_gps = true;
resetHorizontalPositionTo(position, pos_obs_var);
_aid_src_gnss_pos.time_last_fuse = _time_delayed_us;
}
} else {
stopGpsFusion();
_warning_events.flags.gps_quality_poor = true;
ECL_WARN("GPS quality poor - stopping use");
}
} else { // mandatory conditions are not passing
stopGpsFusion();
}
} else {
if (starting_conditions_passing) {
ECL_INFO("starting GPS fusion");
_information_events.flags.starting_gps_fusion = true;
// when already using another velocity source velocity reset is not necessary
if (!isHorizontalAidingActive()
|| isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max)
|| !_control_status_prev.flags.yaw_align
) {
// reset velocity
_information_events.flags.reset_vel_to_gps = true;
resetVelocityTo(velocity, vel_obs_var);
_aid_src_gnss_vel.time_last_fuse = _time_delayed_us;
}
// reset position
_information_events.flags.reset_pos_to_gps = true;
resetHorizontalPositionTo(position, pos_obs_var);
_aid_src_gnss_pos.time_last_fuse = _time_delayed_us;
_control_status.flags.gps = true;
}
}
} else if (_control_status.flags.gps && !isNewestSampleRecent(_time_last_gps_buffer_push, (uint64_t)10e6)) {
stopGpsFusion();
_warning_events.flags.gps_data_stopped = true;
ECL_WARN("GPS data stopped");
} else if (_control_status.flags.gps && !isNewestSampleRecent(_time_last_gps_buffer_push, (uint64_t)1e6)
&& isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
// Handle the case where we are fusing another position source along GPS,
// stop waiting for GPS after 1 s of lost signal
stopGpsFusion();
_warning_events.flags.gps_data_stopped_using_alternate = true;
ECL_WARN("GPS data stopped, using only EV, OF or air data");
}
}
bool Ekf::shouldResetGpsFusion() const
{
/* We are relying on aiding to constrain drift so after a specified time
* with no aiding we need to do something
*/
bool has_horizontal_aiding_timed_out = isTimedOut(_time_last_hor_pos_fuse, _params.reset_timeout_max)
&& isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max);
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
if (has_horizontal_aiding_timed_out) {
// horizontal aiding hasn't timed out if optical flow still active
if (_control_status.flags.opt_flow && isRecent(_aid_src_optical_flow.time_last_fuse, _params.reset_timeout_max)) {
has_horizontal_aiding_timed_out = false;
}
}
#endif // CONFIG_EKF2_OPTICAL_FLOW
const bool is_reset_required = has_horizontal_aiding_timed_out
|| isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max);
const bool is_inflight_nav_failure = _control_status.flags.in_air
&& isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max)
&& isTimedOut(_time_last_hor_pos_fuse, _params.reset_timeout_max)
&& (_time_last_hor_vel_fuse > _time_last_on_ground_us)
&& (_time_last_hor_pos_fuse > _time_last_on_ground_us);
return (is_reset_required || is_inflight_nav_failure);
}
bool Ekf::isYawFailure() const
{
if (!isYawEmergencyEstimateAvailable()) {
return false;
}
const float euler_yaw = getEulerYaw(_R_to_earth);
const float yaw_error = wrap_pi(euler_yaw - _yawEstimator.getYaw());
return fabsf(yaw_error) > math::radians(25.f);
}
#if defined(CONFIG_EKF2_GNSS_YAW)
void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passing, bool gps_checks_failing)
{
if (!(_params.gnss_ctrl & GnssCtrl::YAW)
|| _control_status.flags.gps_yaw_fault) {
stopGpsYawFusion();
return;
}
updateGpsYaw(gps_sample);
const bool is_new_data_available = PX4_ISFINITE(gps_sample.yaw);
if (is_new_data_available) {
const bool continuing_conditions_passing = !gps_checks_failing;
const bool is_gps_yaw_data_intermittent = !isNewestSampleRecent(_time_last_gps_yaw_buffer_push,
2 * GNSS_YAW_MAX_INTERVAL);
const bool starting_conditions_passing = continuing_conditions_passing
&& _control_status.flags.tilt_align
&& gps_checks_passing
&& !is_gps_yaw_data_intermittent
&& !_gps_intermittent;
if (_control_status.flags.gps_yaw) {
if (continuing_conditions_passing) {
fuseGpsYaw();
const bool is_fusion_failing = isTimedOut(_aid_src_gnss_yaw.time_last_fuse, _params.reset_timeout_max);
if (is_fusion_failing) {
if (_nb_gps_yaw_reset_available > 0) {
// Data seems good, attempt a reset
resetYawToGps(gps_sample.yaw);
if (_control_status.flags.in_air) {
_nb_gps_yaw_reset_available--;
}
} else if (starting_conditions_passing) {
// Data seems good, but previous reset did not fix the issue
// something else must be wrong, declare the sensor faulty and stop the fusion
_control_status.flags.gps_yaw_fault = true;
stopGpsYawFusion();
} else {
// A reset did not fix the issue but all the starting checks are not passing
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
stopGpsYawFusion();
}
// TODO: should we give a new reset credit when the fusion does not fail for some time?
}
} else {
// Stop GPS yaw fusion but do not declare it faulty
stopGpsYawFusion();
}
} else {
if (starting_conditions_passing) {
// Try to activate GPS yaw fusion
if (resetYawToGps(gps_sample.yaw)) {
ECL_INFO("starting GPS yaw fusion");
_aid_src_gnss_yaw.time_last_fuse = _time_delayed_us;
_control_status.flags.gps_yaw = true;
_control_status.flags.yaw_align = true;
_nb_gps_yaw_reset_available = 1;
}
}
}
} else if (_control_status.flags.gps_yaw
&& !isNewestSampleRecent(_time_last_gps_yaw_buffer_push, _params.reset_timeout_max)) {
// No yaw data in the message anymore. Stop until it comes back.
stopGpsYawFusion();
}
}
#endif // CONFIG_EKF2_GNSS_YAW
void Ekf::stopGpsYawFusion()
{
#if defined(CONFIG_EKF2_GNSS_YAW)
if (_control_status.flags.gps_yaw) {
_control_status.flags.gps_yaw = false;
resetEstimatorAidStatus(_aid_src_gnss_yaw);
// Before takeoff, we do not want to continue to rely on the current heading
// if we had to stop the fusion
if (!_control_status.flags.in_air) {
ECL_INFO("stopping GPS yaw fusion, clearing yaw alignment");
_control_status.flags.yaw_align = false;
} else {
ECL_INFO("stopping GPS yaw fusion");
}
}
#endif // CONFIG_EKF2_GNSS_YAW
}
void Ekf::stopGpsFusion()
{
if (_control_status.flags.gps) {
ECL_INFO("stopping GPS position and velocity fusion");
resetEstimatorAidStatus(_aid_src_gnss_pos);
resetEstimatorAidStatus(_aid_src_gnss_vel);
_control_status.flags.gps = false;
}
stopGpsHgtFusion();
stopGpsYawFusion();
}