Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/ekf_check.cpp
9447 views
1
#include "Copter.h"
2
3
/**
4
*
5
* Detects failures of the ekf or inertial nav system triggers an alert
6
* to the pilot and helps take countermeasures
7
*
8
*/
9
10
#ifndef EKF_CHECK_ITERATIONS_MAX
11
# define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure
12
#endif
13
14
#ifndef EKF_CHECK_WARNING_TIME
15
# define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds
16
#endif
17
18
////////////////////////////////////////////////////////////////////////////////
19
// EKF_check structure
20
////////////////////////////////////////////////////////////////////////////////
21
static struct {
22
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
23
bool bad_variance; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
24
bool has_ever_passed; // true if the ekf checks have ever passed
25
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
26
} ekf_check_state;
27
28
// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe
29
// should be called at 10hz
30
void Copter::ekf_check()
31
{
32
// ensure EKF_CHECK_ITERATIONS_MAX is at least 7
33
static_assert(EKF_CHECK_ITERATIONS_MAX >= 7, "EKF_CHECK_ITERATIONS_MAX must be at least 7");
34
35
// exit immediately if ekf has no origin yet - this assumes the origin can never become unset
36
Location temp_loc;
37
if (!ahrs.get_origin(temp_loc)) {
38
return;
39
}
40
41
// return immediately if ekf check is disabled
42
if (g.fs_ekf_thresh <= 0.0f) {
43
ekf_check_state.fail_count = 0;
44
ekf_check_state.bad_variance = false;
45
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
46
failsafe_ekf_off_event(); // clear failsafe
47
return;
48
}
49
50
// compare compass and velocity variance vs threshold and also check
51
// if we has a position estimate
52
const bool over_threshold = ekf_over_threshold();
53
const bool has_position = ekf_has_relative_position() || ekf_has_absolute_position();
54
const bool checks_passed = !over_threshold && has_position;
55
56
// return if ekf checks have never passed
57
ekf_check_state.has_ever_passed |= checks_passed;
58
if (!ekf_check_state.has_ever_passed) {
59
return;
60
}
61
62
// increment or decrement counters and take action
63
if (!checks_passed) {
64
// if variances are not yet flagged as bad
65
if (!ekf_check_state.bad_variance) {
66
// increase counter
67
ekf_check_state.fail_count++;
68
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-2) && over_threshold) {
69
// we are two iterations away from declaring an EKF failsafe, ask the EKF if we can reset
70
// yaw to resolve the issue
71
ahrs.request_yaw_reset();
72
}
73
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-1)) {
74
// we are just about to declare a EKF failsafe, ask the EKF if we can
75
// change lanes to resolve the issue
76
ahrs.check_lane_switch();
77
}
78
// if counter above max then trigger failsafe
79
if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {
80
// limit count from climbing too high
81
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
82
ekf_check_state.bad_variance = true;
83
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
84
// send message to gcs
85
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
86
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
87
ekf_check_state.last_warn_time = AP_HAL::millis();
88
}
89
failsafe_ekf_event();
90
}
91
}
92
} else {
93
// reduce counter
94
if (ekf_check_state.fail_count > 0) {
95
ekf_check_state.fail_count--;
96
97
// if variances are flagged as bad and the counter reaches zero then clear flag
98
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
99
ekf_check_state.bad_variance = false;
100
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
101
// clear failsafe
102
failsafe_ekf_off_event();
103
}
104
}
105
}
106
107
// set AP_Notify flags
108
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
109
110
// To-Do: add ekf variances to extended status
111
}
112
113
// ekf_over_threshold - returns true if the ekf's variance are over the tolerance
114
bool Copter::ekf_over_threshold()
115
{
116
// use EKF to get variance
117
float position_var, vel_var, height_var, tas_variance;
118
Vector3f mag_variance;
119
variances_valid = ahrs.get_variances(vel_var, position_var, height_var, mag_variance, tas_variance);
120
121
if (!variances_valid) {
122
return false;
123
}
124
125
uint32_t now_us = AP_HAL::micros();
126
float dt = (now_us - last_ekf_check_us) * 1e-6f;
127
128
// always update filtered values as this serves the vibration check as well
129
position_var = pos_variance_filt.apply(position_var, dt);
130
vel_var = vel_variance_filt.apply(vel_var, dt);
131
132
last_ekf_check_us = now_us;
133
134
// return false if disabled
135
if (g.fs_ekf_thresh <= 0.0f) {
136
return false;
137
}
138
139
const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);
140
141
// return true if two of compass, velocity and position variances are over the threshold OR velocity variance is twice the threshold
142
uint8_t over_thresh_count = 0;
143
if (mag_max >= g.fs_ekf_thresh) {
144
over_thresh_count++;
145
}
146
147
bool optflow_healthy = false;
148
#if AP_OPTICALFLOW_ENABLED
149
optflow_healthy = optflow.healthy();
150
#endif
151
if (!optflow_healthy && (vel_var >= (2.0f * g.fs_ekf_thresh))) {
152
over_thresh_count += 2;
153
} else if (vel_var >= g.fs_ekf_thresh) {
154
over_thresh_count++;
155
}
156
157
if ((position_var >= g.fs_ekf_thresh && over_thresh_count >= 1) || over_thresh_count >= 2) {
158
return true;
159
}
160
161
return false;
162
}
163
164
165
// failsafe_ekf_event - perform ekf failsafe
166
void Copter::failsafe_ekf_event()
167
{
168
// EKF failsafe event has occurred
169
failsafe.ekf = true;
170
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
171
172
// if disarmed take no action
173
if (!motors->armed()) {
174
return;
175
}
176
177
// set true if ekf failsafe is triggered
178
AP_Notify::flags.failsafe_ekf = true;
179
180
// True if no action should be taken
181
const bool report_only = g.fs_ekf_action == FS_EKF_ACTION_REPORT_ONLY;
182
183
// sometimes LAND *does* require GPS so ensure we are in non-GPS land
184
const bool landing_with_position = landing_with_GPS();
185
if (landing_with_position && !report_only) {
186
mode_land.do_not_use_GPS();
187
}
188
189
// does this mode require position?
190
const bool no_action_in_current_mode = !copter.flightmode->requires_position() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE);
191
192
if (report_only || landing_with_position || no_action_in_current_mode) {
193
gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe");
194
return;
195
}
196
197
// take action based on fs_ekf_action parameter
198
switch (g.fs_ekf_action) {
199
case FS_EKF_ACTION_REPORT_ONLY:
200
// Should have early returned above
201
break;
202
case FS_EKF_ACTION_ALTHOLD:
203
// AltHold
204
if (failsafe.radio || !set_mode(Mode::Number::ALT_HOLD, ModeReason::EKF_FAILSAFE)) {
205
set_mode_land_with_pause(ModeReason::EKF_FAILSAFE);
206
}
207
break;
208
case FS_EKF_ACTION_LAND:
209
case FS_EKF_ACTION_LAND_EVEN_STABILIZE:
210
default:
211
set_mode_land_with_pause(ModeReason::EKF_FAILSAFE);
212
break;
213
}
214
215
gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe: changed to %s Mode", flightmode->name());
216
}
217
218
// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared
219
void Copter::failsafe_ekf_off_event(void)
220
{
221
// return immediately if not in ekf failsafe
222
if (!failsafe.ekf) {
223
return;
224
}
225
226
failsafe.ekf = false;
227
if (AP_Notify::flags.failsafe_ekf) {
228
AP_Notify::flags.failsafe_ekf = false;
229
gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe Cleared");
230
}
231
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
232
}
233
234
// re-check if the flight mode requires GPS but EKF failsafe is active
235
// this should be called by flight modes that are changing their submode from one that does NOT require a position estimate to one that does
236
void Copter::failsafe_ekf_recheck()
237
{
238
// return immediately if not in ekf failsafe
239
if (!failsafe.ekf) {
240
return;
241
}
242
243
// trigger EKF failsafe action
244
failsafe_ekf_event();
245
}
246
247
// check for ekf yaw reset and adjust target heading, also log position reset
248
void Copter::check_ekf_reset()
249
{
250
// check for yaw reset
251
float yaw_angle_change_rad;
252
uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);
253
if (new_ekfYawReset_ms != ekfYawReset_ms) {
254
attitude_control->inertial_frame_reset();
255
ekfYawReset_ms = new_ekfYawReset_ms;
256
LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);
257
}
258
259
// check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment
260
if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) {
261
attitude_control->inertial_frame_reset();
262
ekf_primary_core = ahrs.get_primary_core_index();
263
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core));
264
gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);
265
}
266
}
267
268
// check for high vibrations affecting altitude control
269
void Copter::check_vibration()
270
{
271
uint32_t now = AP_HAL::millis();
272
273
// assume checks will succeed
274
bool innovation_checks_valid = true;
275
276
// check if vertical velocity and position innovations are positive (NKF3.IVD & NKF3.IPD are both positive)
277
Vector3f vel_innovation;
278
Vector3f pos_innovation;
279
Vector3f mag_innovation;
280
float tas_innovation;
281
float yaw_innovation;
282
if (!ahrs.get_innovations(vel_innovation, pos_innovation, mag_innovation, tas_innovation, yaw_innovation)) {
283
innovation_checks_valid = false;
284
}
285
const bool innov_velD_posD_positive = is_positive(vel_innovation.z) && is_positive(pos_innovation.z);
286
287
// check if vertical velocity variance is at least 1 (NK4.SV >= 1.0)
288
// filtered variances are updated in ekf_check() which runs at the same rate (10Hz) as this check
289
if (!variances_valid) {
290
innovation_checks_valid = false;
291
}
292
const bool is_vibration_affected = ahrs.is_vibration_affected();
293
const bool bad_vibe_detected = (innovation_checks_valid && innov_velD_posD_positive && (vel_variance_filt.get() > 1.0f)) || is_vibration_affected;
294
const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed() && !flightmode->has_manual_throttle();
295
296
if (!vibration_check.high_vibes) {
297
// initialise timers
298
if (!do_bad_vibe_actions) {
299
vibration_check.start_ms = now;
300
}
301
// check if failure has persisted for at least 1 second
302
if (now - vibration_check.start_ms > 1000) {
303
// switch position controller to use resistant gains
304
vibration_check.clear_ms = 0;
305
vibration_check.high_vibes = true;
306
pos_control->set_vibe_comp(true);
307
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED);
308
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON");
309
}
310
} else {
311
// initialise timer
312
if (do_bad_vibe_actions) {
313
vibration_check.clear_ms = now;
314
}
315
// turn off vibration compensation after 15 seconds
316
if (now - vibration_check.clear_ms > 15000) {
317
// restore position controller gains, reset timers and update user
318
vibration_check.start_ms = 0;
319
vibration_check.high_vibes = false;
320
pos_control->set_vibe_comp(false);
321
vibration_check.clear_ms = 0;
322
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED);
323
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF");
324
}
325
}
326
327
return;
328
}
329
330