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/Blimp/ekf_check.cpp
Views: 1798
1
#include "Blimp.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
uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
24
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
25
} ekf_check_state;
26
27
// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe
28
// should be called at 10hz
29
void Blimp::ekf_check()
30
{
31
// ensure EKF_CHECK_ITERATIONS_MAX is at least 7
32
static_assert(EKF_CHECK_ITERATIONS_MAX >= 7, "EKF_CHECK_ITERATIONS_MAX must be at least 7");
33
34
// exit immediately if ekf has no origin yet - this assumes the origin can never become unset
35
Location temp_loc;
36
if (!ahrs.get_origin(temp_loc)) {
37
return;
38
}
39
40
// return immediately if motors are not armed, or ekf check is disabled
41
if (!motors->armed() || (g.fs_ekf_thresh <= 0.0f)) {
42
ekf_check_state.fail_count = 0;
43
ekf_check_state.bad_variance = false;
44
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
45
failsafe_ekf_off_event(); // clear failsafe
46
return;
47
}
48
49
// compare compass and velocity variance vs threshold and also check
50
// if we are still navigating
51
bool is_navigating = ekf_has_relative_position() || ekf_has_absolute_position();
52
if (ekf_over_threshold() || !is_navigating) {
53
// if compass is not yet flagged as bad
54
if (!ekf_check_state.bad_variance) {
55
// increase counter
56
ekf_check_state.fail_count++;
57
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-2) && ekf_over_threshold()) {
58
// we are two iterations away from declaring an EKF failsafe, ask the EKF if we can reset
59
// yaw to resolve the issue
60
ahrs.request_yaw_reset();
61
}
62
if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-1)) {
63
// we are just about to declare a EKF failsafe, ask the EKF if we can
64
// change lanes to resolve the issue
65
ahrs.check_lane_switch();
66
}
67
// if counter above max then trigger failsafe
68
if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {
69
// limit count from climbing too high
70
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
71
ekf_check_state.bad_variance = true;
72
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
73
// send message to gcs
74
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
75
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
76
ekf_check_state.last_warn_time = AP_HAL::millis();
77
}
78
failsafe_ekf_event();
79
}
80
}
81
} else {
82
// reduce counter
83
if (ekf_check_state.fail_count > 0) {
84
ekf_check_state.fail_count--;
85
86
// if compass is flagged as bad and the counter reaches zero then clear flag
87
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
88
ekf_check_state.bad_variance = false;
89
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
90
// clear failsafe
91
failsafe_ekf_off_event();
92
}
93
}
94
}
95
96
// set AP_Notify flags
97
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
98
99
// To-Do: add ekf variances to extended status
100
}
101
102
// ekf_over_threshold - returns true if the ekf's variance are over the tolerance
103
bool Blimp::ekf_over_threshold()
104
{
105
// return false immediately if disabled
106
if (g.fs_ekf_thresh <= 0.0f) {
107
return false;
108
}
109
110
// use EKF to get variance
111
float position_variance, vel_variance, height_variance, tas_variance;
112
Vector3f mag_variance;
113
ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance);
114
115
const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);
116
117
// return true if two of compass, velocity and position variances are over the threshold OR velocity variance is twice the threshold
118
uint8_t over_thresh_count = 0;
119
if (mag_max >= g.fs_ekf_thresh) {
120
over_thresh_count++;
121
}
122
123
bool optflow_healthy = false;
124
if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) {
125
over_thresh_count += 2;
126
} else if (vel_variance >= g.fs_ekf_thresh) {
127
over_thresh_count++;
128
}
129
130
if ((position_variance >= g.fs_ekf_thresh && over_thresh_count >= 1) || over_thresh_count >= 2) {
131
return true;
132
}
133
134
return false;
135
}
136
137
138
// failsafe_ekf_event - perform ekf failsafe
139
void Blimp::failsafe_ekf_event()
140
{
141
// return immediately if ekf failsafe already triggered
142
if (failsafe.ekf) {
143
return;
144
}
145
146
// EKF failsafe event has occurred
147
failsafe.ekf = true;
148
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
149
150
// does this mode require position?
151
if (!blimp.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_MANUAL)) {
152
return;
153
}
154
155
// take action based on fs_ekf_action parameter
156
switch (g.fs_ekf_action) {
157
case FS_EKF_ACTION_LAND:
158
case FS_EKF_ACTION_LAND_EVEN_MANUAL:
159
default:
160
set_mode_land_failsafe(ModeReason::EKF_FAILSAFE);
161
break;
162
}
163
}
164
165
// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared
166
void Blimp::failsafe_ekf_off_event(void)
167
{
168
// return immediately if not in ekf failsafe
169
if (!failsafe.ekf) {
170
return;
171
}
172
173
failsafe.ekf = false;
174
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
175
}
176
177
// check for ekf yaw reset and adjust target heading, also log position reset
178
void Blimp::check_ekf_reset()
179
{
180
// check for yaw reset
181
float yaw_angle_change_rad;
182
uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);
183
if (new_ekfYawReset_ms != ekfYawReset_ms) {
184
ekfYawReset_ms = new_ekfYawReset_ms;
185
LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);
186
}
187
188
// check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment
189
if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) {
190
ekf_primary_core = ahrs.get_primary_core_index();
191
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core));
192
gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);
193
}
194
}
195
196
// check for high vibrations affecting altitude control
197
void Blimp::check_vibration()
198
{
199
uint32_t now = AP_HAL::millis();
200
201
// assume checks will succeed
202
bool checks_succeeded = true;
203
204
// check if vertical velocity and position innovations are positive (NKF3.IVD & NKF3.IPD are both positive)
205
Vector3f vel_innovation;
206
Vector3f pos_innovation;
207
Vector3f mag_innovation;
208
float tas_innovation;
209
float yaw_innovation;
210
if (!ahrs.get_innovations(vel_innovation, pos_innovation, mag_innovation, tas_innovation, yaw_innovation)) {
211
checks_succeeded = false;
212
}
213
const bool innov_velD_posD_positive = is_positive(vel_innovation.z) && is_positive(pos_innovation.z);
214
215
// check if vertical velocity variance is at least 1 (NK4.SV >= 1.0)
216
float position_variance, vel_variance, height_variance, tas_variance;
217
Vector3f mag_variance;
218
if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance)) {
219
checks_succeeded = false;
220
}
221
222
// if no failure
223
if ((g2.fs_vibe_enabled == 0) || !checks_succeeded || !motors->armed() || !innov_velD_posD_positive || (vel_variance < 1.0f)) {
224
if (vibration_check.high_vibes) {
225
// start clear time
226
if (vibration_check.clear_ms == 0) {
227
vibration_check.clear_ms = now;
228
return;
229
}
230
// turn off vibration compensation after 15 seconds
231
if (now - vibration_check.clear_ms > 15000) {
232
// restore ekf gains, reset timers and update user
233
vibration_check.high_vibes = false;
234
vibration_check.clear_ms = 0;
235
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED);
236
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF");
237
}
238
}
239
vibration_check.start_ms = 0;
240
return;
241
}
242
243
// start timer
244
if (vibration_check.start_ms == 0) {
245
vibration_check.start_ms = now;
246
vibration_check.clear_ms = 0;
247
return;
248
}
249
250
// check if failure has persisted for at least 1 second
251
if (now - vibration_check.start_ms > 1000) {
252
if (!vibration_check.high_vibes) {
253
// switch ekf to use resistant gains
254
vibration_check.high_vibes = true;
255
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED);
256
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON");
257
}
258
}
259
}
260
261