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/ArduCopter/crash_check.cpp
Views: 1798
1
#include "Copter.h"
2
3
// Code to detect a crash main ArduCopter code
4
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
5
#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond target angle is signal we are out of control
6
#define CRASH_CHECK_ANGLE_MIN_DEG 15.0f // vehicle must be leaning at least 15deg to trigger crash check
7
#define CRASH_CHECK_SPEED_MAX 10.0f // vehicle must be moving at less than 10m/s to trigger crash check
8
#define CRASH_CHECK_ACCEL_MAX 3.0f // vehicle must be accelerating less than 3m/s/s to be considered crashed
9
10
// Code to detect a thrust loss main ArduCopter code
11
#define THRUST_LOSS_CHECK_TRIGGER_SEC 1 // 1 second descent while level and high throttle indicates thrust loss
12
#define THRUST_LOSS_CHECK_ANGLE_DEVIATION_CD 1500 // we can't expect to maintain altitude beyond 15 degrees on all aircraft
13
#define THRUST_LOSS_CHECK_MINIMUM_THROTTLE 0.9f // we can expect to maintain altitude above 90 % throttle
14
15
// Yaw imbalance check
16
#define YAW_IMBALANCE_IMAX_THRESHOLD 0.75f
17
#define YAW_IMBALANCE_WARN_MS 10000
18
19
// crash_check - disarms motors if a crash has been detected
20
// crashes are detected by the vehicle being more than 20 degrees beyond it's angle limits continuously for more than 1 second
21
// called at MAIN_LOOP_RATE
22
void Copter::crash_check()
23
{
24
static uint16_t crash_counter; // number of iterations vehicle may have been crashed
25
26
// return immediately if disarmed, or crash checking disabled
27
if (!motors->armed() || ap.land_complete || g.fs_crash_check == 0) {
28
crash_counter = 0;
29
return;
30
}
31
32
// exit immediately if in standby
33
if (standby_active) {
34
crash_counter = 0;
35
return;
36
}
37
38
// exit immediately if in force flying
39
if (get_force_flying() && !flightmode->is_landing()) {
40
crash_counter = 0;
41
return;
42
}
43
44
// return immediately if we are not in an angle stabilize flight mode or we are flipping
45
if (!flightmode->crash_check_enabled()) {
46
crash_counter = 0;
47
return;
48
}
49
50
#if MODE_AUTOROTATE_ENABLED
51
//return immediately if in autorotation mode
52
if (flightmode->mode_number() == Mode::Number::AUTOROTATE) {
53
crash_counter = 0;
54
return;
55
}
56
#endif
57
58
// vehicle not crashed if 1hz filtered acceleration is more than 3m/s (1G on Z-axis has been subtracted)
59
const float filtered_acc = land_accel_ef_filter.get().length();
60
if (filtered_acc >= CRASH_CHECK_ACCEL_MAX) {
61
crash_counter = 0;
62
return;
63
}
64
65
// check for lean angle over 15 degrees
66
const float lean_angle_deg = degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()));
67
if (lean_angle_deg <= CRASH_CHECK_ANGLE_MIN_DEG) {
68
crash_counter = 0;
69
return;
70
}
71
72
// check for angle error over 30 degrees
73
const float angle_error = attitude_control->get_att_error_angle_deg();
74
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
75
crash_counter = 0;
76
return;
77
}
78
79
// check for speed under 10m/s (if available)
80
Vector3f vel_ned;
81
if (ahrs.get_velocity_NED(vel_ned) && (vel_ned.length() >= CRASH_CHECK_SPEED_MAX)) {
82
crash_counter = 0;
83
return;
84
}
85
86
// we may be crashing
87
crash_counter++;
88
89
// check if crashing for 2 seconds
90
if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
91
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
92
// send message to gcs
93
gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming: AngErr=%.0f>%.0f, Accel=%.1f<%.1f", angle_error, CRASH_CHECK_ANGLE_DEVIATION_DEG, filtered_acc, CRASH_CHECK_ACCEL_MAX);
94
// disarm motors
95
copter.arming.disarm(AP_Arming::Method::CRASH);
96
}
97
}
98
99
// check for loss of thrust and trigger thrust boost in motors library
100
void Copter::thrust_loss_check()
101
{
102
static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed
103
104
// no-op if suppressed by flight options param
105
if (copter.option_is_enabled(FlightOption::DISABLE_THRUST_LOSS_CHECK)) {
106
return;
107
}
108
109
// exit immediately if thrust boost is already engaged
110
if (motors->get_thrust_boost()) {
111
return;
112
}
113
114
// return immediately if disarmed
115
if (!motors->armed() || ap.land_complete) {
116
thrust_loss_counter = 0;
117
return;
118
}
119
120
// exit immediately if in standby
121
if (standby_active) {
122
return;
123
}
124
125
// check for desired angle over 15 degrees
126
// todo: add thrust angle to AC_AttitudeControl
127
const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
128
if (sq(angle_target.x) + sq(angle_target.y) > sq(THRUST_LOSS_CHECK_ANGLE_DEVIATION_CD)) {
129
thrust_loss_counter = 0;
130
return;
131
}
132
133
// check for throttle over 90% or throttle saturation
134
if ((attitude_control->get_throttle_in() < THRUST_LOSS_CHECK_MINIMUM_THROTTLE) && (!motors->limit.throttle_upper)) {
135
thrust_loss_counter = 0;
136
return;
137
}
138
139
// check throttle is over 25% to prevent checks triggering from thrust limitations caused by low commanded throttle
140
if ((attitude_control->get_throttle_in() < 0.25f)) {
141
thrust_loss_counter = 0;
142
return;
143
}
144
145
// check for descent
146
if (!is_negative(inertial_nav.get_velocity_z_up_cms())) {
147
thrust_loss_counter = 0;
148
return;
149
}
150
151
// check for angle error over 30 degrees to ensure the aircraft has attitude control
152
const float angle_error = attitude_control->get_att_error_angle_deg();
153
if (angle_error >= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
154
thrust_loss_counter = 0;
155
return;
156
}
157
158
// the aircraft is descending with low requested roll and pitch, at full available throttle, with attitude control
159
// we may have lost thrust
160
thrust_loss_counter++;
161
162
// check if thrust loss for 1 second
163
if (thrust_loss_counter >= (THRUST_LOSS_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
164
// reset counter
165
thrust_loss_counter = 0;
166
LOGGER_WRITE_ERROR(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED);
167
// send message to gcs
168
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1);
169
// enable thrust loss handling
170
motors->set_thrust_boost(true);
171
// the motors library disables this when it is no longer needed to achieve the commanded output
172
173
#if AP_GRIPPER_ENABLED
174
if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) {
175
gripper.release();
176
}
177
#endif
178
}
179
}
180
181
// check for a large yaw imbalance, could be due to badly calibrated ESC or misaligned motors
182
void Copter::yaw_imbalance_check()
183
{
184
// no-op if suppressed by flight options param
185
if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) {
186
return;
187
}
188
189
// If I is disabled it is unlikely that the issue is not obvious
190
if (!is_positive(attitude_control->get_rate_yaw_pid().kI())) {
191
return;
192
}
193
194
// thrust loss is triggered, yaw issues are expected
195
if (motors->get_thrust_boost()) {
196
yaw_I_filt.reset(0.0f);
197
return;
198
}
199
200
// return immediately if disarmed
201
if (!motors->armed() || ap.land_complete) {
202
yaw_I_filt.reset(0.0f);
203
return;
204
}
205
206
// exit immediately if in standby
207
if (standby_active) {
208
yaw_I_filt.reset(0.0f);
209
return;
210
}
211
212
// magnitude of low pass filtered I term
213
const float I_term = attitude_control->get_rate_yaw_pid().get_pid_info().I;
214
const float I = fabsf(yaw_I_filt.apply(attitude_control->get_rate_yaw_pid().get_pid_info().I,G_Dt));
215
if (I > fabsf(I_term)) {
216
// never allow to be larger than I
217
yaw_I_filt.reset(I_term);
218
}
219
220
const float I_max = attitude_control->get_rate_yaw_pid().imax();
221
if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max))))) {
222
// filtered using over percentage of I max or unfiltered = I max
223
// I makes up more than percentage of total available control power
224
const uint32_t now = millis();
225
if (now - last_yaw_warn_ms > YAW_IMBALANCE_WARN_MS) {
226
last_yaw_warn_ms = now;
227
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Yaw Imbalance %0.0f%%", I *100);
228
}
229
}
230
}
231
232
#if HAL_PARACHUTE_ENABLED
233
234
// Code to detect a crash main ArduCopter code
235
#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute
236
#define PARACHUTE_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees off from target indicates a loss of control
237
238
// parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected
239
// vehicle is considered to have a "serious loss of control" by the vehicle being more than 30 degrees off from the target roll and pitch angles continuously for 1 second
240
// called at MAIN_LOOP_RATE
241
void Copter::parachute_check()
242
{
243
static uint16_t control_loss_count; // number of iterations we have been out of control
244
static int32_t baro_alt_start;
245
246
// exit immediately if parachute is not enabled
247
if (!parachute.enabled()) {
248
return;
249
}
250
251
// pass is_flying to parachute library
252
parachute.set_is_flying(!ap.land_complete);
253
254
// pass sink rate to parachute library
255
parachute.set_sink_rate(-inertial_nav.get_velocity_z_up_cms() * 0.01f);
256
257
// exit immediately if in standby
258
if (standby_active) {
259
return;
260
}
261
262
// call update to give parachute a chance to move servo or relay back to off position
263
parachute.update();
264
265
// return immediately if motors are not armed or pilot's throttle is above zero
266
if (!motors->armed()) {
267
control_loss_count = 0;
268
return;
269
}
270
271
if (parachute.release_initiated()) {
272
return;
273
}
274
275
// return immediately if we are not in an angle stabilize flight mode or we are flipping
276
if (!flightmode->crash_check_enabled()) {
277
control_loss_count = 0;
278
return;
279
}
280
281
// ensure we are flying
282
if (ap.land_complete) {
283
control_loss_count = 0;
284
return;
285
}
286
287
// ensure the first control_loss event is from above the min altitude
288
if (control_loss_count == 0 && parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100)) {
289
return;
290
}
291
292
// trigger parachute release based on sink rate
293
parachute.check_sink_rate();
294
295
// check for angle error over 30 degrees
296
const float angle_error = attitude_control->get_att_error_angle_deg();
297
if (angle_error <= PARACHUTE_CHECK_ANGLE_DEVIATION_DEG) {
298
if (control_loss_count > 0) {
299
control_loss_count--;
300
}
301
return;
302
}
303
304
// increment counter
305
if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
306
control_loss_count++;
307
}
308
309
// record baro alt if we have just started losing control
310
if (control_loss_count == 1) {
311
baro_alt_start = baro_alt;
312
313
// exit if baro altitude change indicates we are not falling
314
} else if (baro_alt >= baro_alt_start) {
315
control_loss_count = 0;
316
return;
317
318
// To-Do: add check that the vehicle is actually falling
319
320
// check if loss of control for at least 1 second
321
} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
322
// reset control loss counter
323
control_loss_count = 0;
324
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL);
325
// release parachute
326
parachute_release();
327
}
328
}
329
330
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
331
void Copter::parachute_release()
332
{
333
// release parachute
334
parachute.release();
335
336
#if AP_LANDINGGEAR_ENABLED
337
// deploy landing gear
338
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
339
#endif
340
}
341
342
// parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error
343
// checks if the vehicle is landed
344
void Copter::parachute_manual_release()
345
{
346
// exit immediately if parachute is not enabled
347
if (!parachute.enabled()) {
348
return;
349
}
350
351
// do not release if vehicle is landed
352
// do not release if we are landed or below the minimum altitude above home
353
if (ap.land_complete) {
354
// warn user of reason for failure
355
gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed");
356
LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED);
357
return;
358
}
359
360
// do not release if we are landed or below the minimum altitude above home
361
if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {
362
// warn user of reason for failure
363
gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");
364
LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW);
365
return;
366
}
367
368
// if we get this far release parachute
369
parachute_release();
370
}
371
372
#endif // HAL_PARACHUTE_ENABLED
373
374