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/Rover/ekf_check.cpp
Views: 1798
1
#include "Rover.h"
2
3
/**
4
*
5
* Detects failures of the ekf and triggers a failsafe
6
*
7
*/
8
9
#ifndef EKF_CHECK_ITERATIONS_MAX
10
# define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure
11
#endif
12
13
#ifndef EKF_CHECK_WARNING_TIME
14
# define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds
15
#endif
16
17
18
// EKF_check structure
19
static struct {
20
uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
21
uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
22
uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
23
} ekf_check_state;
24
25
// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe
26
// should be called at 10hz
27
void Rover::ekf_check()
28
{
29
// exit immediately if ekf has no origin yet - this assumes the origin can never become unset
30
Location temp_loc;
31
if (!ahrs.get_origin(temp_loc)) {
32
return;
33
}
34
35
// return immediately if motors are not armed, or ekf check is disabled
36
if (!arming.is_armed() || (g.fs_ekf_thresh <= 0.0f)) {
37
ekf_check_state.fail_count = 0;
38
ekf_check_state.bad_variance = false;
39
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
40
failsafe_ekf_off_event(); // clear failsafe
41
return;
42
}
43
44
// compare compass and velocity variance vs threshold
45
if (ekf_over_threshold()) {
46
// if compass is not yet flagged as bad
47
if (!ekf_check_state.bad_variance) {
48
// increase counter
49
ekf_check_state.fail_count++;
50
// if counter above max then trigger failsafe
51
if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {
52
// limit count from climbing too high
53
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
54
ekf_check_state.bad_variance = true;
55
56
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,
57
LogErrorCode::EKFCHECK_BAD_VARIANCE);
58
// send message to gcs
59
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
60
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
61
ekf_check_state.last_warn_time = AP_HAL::millis();
62
}
63
failsafe_ekf_event();
64
}
65
}
66
} else {
67
// reduce counter
68
if (ekf_check_state.fail_count > 0) {
69
ekf_check_state.fail_count--;
70
71
// if variance is flagged as bad and the counter reaches zero then clear flag
72
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
73
ekf_check_state.bad_variance = false;
74
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,
75
LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
76
// clear failsafe
77
failsafe_ekf_off_event();
78
}
79
}
80
}
81
82
// set AP_Notify flags
83
AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;
84
}
85
86
// returns true if the ekf's variance are over the tolerance
87
bool Rover::ekf_over_threshold()
88
{
89
// return false immediately if disabled
90
if (g.fs_ekf_thresh <= 0.0f) {
91
return false;
92
}
93
94
// use EKF to get variance
95
float position_variance, vel_variance, height_variance, tas_variance;
96
Vector3f mag_variance;
97
ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance);
98
99
// return true if two of compass, velocity and position variances are over the threshold
100
uint8_t over_thresh_count = 0;
101
if (mag_variance.length() >= g.fs_ekf_thresh) {
102
over_thresh_count++;
103
}
104
if (vel_variance >= g.fs_ekf_thresh) {
105
over_thresh_count++;
106
}
107
if (position_variance >= g.fs_ekf_thresh) {
108
over_thresh_count++;
109
}
110
111
bool optflow_healthy = false;
112
#if AP_OPTICALFLOW_ENABLED
113
optflow_healthy = optflow.healthy();
114
#endif
115
if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) {
116
over_thresh_count += 2;
117
} else if (vel_variance >= g.fs_ekf_thresh) {
118
over_thresh_count++;
119
}
120
121
if (over_thresh_count >= 2) {
122
return true;
123
}
124
125
return !ekf_position_ok();
126
}
127
128
// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set
129
bool Rover::ekf_position_ok()
130
{
131
if (!ahrs.have_inertial_nav()) {
132
// do not allow navigation with dcm position
133
return false;
134
}
135
136
// get EKF filter status
137
nav_filter_status filt_status;
138
rover.ahrs.get_filter_status(filt_status);
139
140
// if disarmed we accept a predicted horizontal absolute or relative position
141
if (!arming.is_armed()) {
142
return (filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs || filt_status.flags.horiz_pos_rel || filt_status.flags.pred_horiz_pos_rel);
143
} else {
144
// once armed we require a good absolute or relative position and EKF must not be in const_pos_mode
145
return ((filt_status.flags.horiz_pos_abs || filt_status.flags.horiz_pos_rel) && !filt_status.flags.const_pos_mode);
146
}
147
}
148
149
// perform ekf failsafe
150
void Rover::failsafe_ekf_event()
151
{
152
// return immediately if ekf failsafe already triggered
153
if (failsafe.ekf) {
154
return;
155
}
156
157
// EKF failsafe event has occurred
158
failsafe.ekf = true;
159
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,
160
LogErrorCode::FAILSAFE_OCCURRED);
161
162
// does this mode require position?
163
if (!control_mode->requires_position()) {
164
return;
165
}
166
167
// take action based on fs_ekf_action parameter
168
switch ((enum fs_ekf_action)g.fs_ekf_action.get()) {
169
case FS_EKF_DISABLE:
170
// do nothing
171
return;
172
case FS_EKF_REPORT_ONLY:
173
break;
174
case FS_EKF_HOLD:
175
default:
176
set_mode(mode_hold, ModeReason::EKF_FAILSAFE);
177
break;
178
}
179
180
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe");
181
}
182
183
// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared
184
void Rover::failsafe_ekf_off_event(void)
185
{
186
// return immediately if not in ekf failsafe
187
if (!failsafe.ekf) {
188
return;
189
}
190
191
failsafe.ekf = false;
192
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,
193
LogErrorCode::FAILSAFE_RESOLVED);
194
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe cleared");
195
}
196
197