Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/crash_check.cpp
9507 views
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_RAD radians(15.0) // 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_rad = attitude_control->get_att_target_euler_rad();
128
if (angle_target_rad.xy().length_squared() > sq(THRUST_LOSS_CHECK_ANGLE_DEVIATION_RAD)) {
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
float vel_d_ms = 0;
147
if (!AP::ahrs().get_velocity_D(vel_d_ms, vibration_check.high_vibes) || !is_positive(vel_d_ms)) {
148
// we have no vertical velocity estimate and/or we are not descending
149
thrust_loss_counter = 0;
150
return;
151
}
152
153
// check for angle error over 30 degrees to ensure the aircraft has attitude control
154
const float angle_error = attitude_control->get_att_error_angle_deg();
155
if (angle_error >= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
156
thrust_loss_counter = 0;
157
return;
158
}
159
160
// the aircraft is descending with low requested roll and pitch, at full available throttle, with attitude control
161
// we may have lost thrust
162
thrust_loss_counter++;
163
164
// check if thrust loss for 1 second
165
if (thrust_loss_counter >= (THRUST_LOSS_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) {
166
// reset counter
167
thrust_loss_counter = 0;
168
LOGGER_WRITE_ERROR(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED);
169
// send message to gcs
170
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1);
171
// enable thrust loss handling
172
motors->set_thrust_boost(true);
173
// the motors library disables this when it is no longer needed to achieve the commanded output
174
175
#if AP_GRIPPER_ENABLED
176
if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) {
177
gripper.release();
178
}
179
#endif
180
}
181
}
182
183
// check for a large yaw imbalance, could be due to badly calibrated ESC or misaligned motors
184
void Copter::yaw_imbalance_check()
185
{
186
// no-op if suppressed by flight options param
187
if (copter.option_is_enabled(FlightOption::DISABLE_YAW_IMBALANCE_WARNING)) {
188
return;
189
}
190
191
// If I is disabled it is unlikely that the issue is not obvious
192
if (!is_positive(attitude_control->get_rate_yaw_pid().kI())) {
193
return;
194
}
195
196
// thrust loss is triggered, yaw issues are expected
197
if (motors->get_thrust_boost()) {
198
yaw_I_filt.reset(0.0f);
199
return;
200
}
201
202
// return immediately if disarmed
203
if (!motors->armed() || ap.land_complete) {
204
yaw_I_filt.reset(0.0f);
205
return;
206
}
207
208
// exit immediately if in standby
209
if (standby_active) {
210
yaw_I_filt.reset(0.0f);
211
return;
212
}
213
214
// magnitude of low pass filtered I term
215
const float I_term = attitude_control->get_rate_yaw_pid().get_pid_info().I;
216
const float I = fabsf(yaw_I_filt.apply(attitude_control->get_rate_yaw_pid().get_pid_info().I,G_Dt));
217
if (I > fabsf(I_term)) {
218
// never allow to be larger than I
219
yaw_I_filt.reset(I_term);
220
}
221
222
const float I_max = attitude_control->get_rate_yaw_pid().imax();
223
if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max))))) {
224
// filtered using over percentage of I max or unfiltered = I max
225
// I makes up more than percentage of total available control power
226
const uint32_t now = millis();
227
if (now - last_yaw_warn_ms > YAW_IMBALANCE_WARN_MS) {
228
last_yaw_warn_ms = now;
229
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Yaw Imbalance %0.0f%%", I *100);
230
}
231
}
232
}
233
234
#if HAL_PARACHUTE_ENABLED
235
236
// Code to detect a crash main ArduCopter code
237
#define PARACHUTE_CHECK_TRIGGER_SEC 1 // 1 second of loss of control triggers the parachute
238
#define PARACHUTE_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees off from target indicates a loss of control
239
240
// parachute_check - disarms motors and triggers the parachute if serious loss of control has been detected
241
// 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
242
// called at MAIN_LOOP_RATE
243
void Copter::parachute_check()
244
{
245
static uint16_t control_loss_count; // number of iterations we have been out of control
246
static float baro_alt_start_m;
247
248
// exit immediately if parachute is not enabled
249
if (!parachute.enabled()) {
250
return;
251
}
252
253
// pass is_flying to parachute library
254
parachute.set_is_flying(!ap.land_complete);
255
256
// pass sink rate to parachute library
257
float vel_d_ms = 0;
258
UNUSED_RESULT(AP::ahrs().get_velocity_D(vel_d_ms, vibration_check.high_vibes));
259
parachute.set_sink_rate(vel_d_ms);
260
261
// exit immediately if in standby
262
if (standby_active) {
263
return;
264
}
265
266
// call update to give parachute a chance to move servo or relay back to off position
267
parachute.update();
268
269
// return immediately if motors are not armed or pilot's throttle is above zero
270
if (!motors->armed()) {
271
control_loss_count = 0;
272
return;
273
}
274
275
if (parachute.release_initiated()) {
276
return;
277
}
278
279
// return immediately if we are not in an angle stabilize flight mode or we are flipping
280
if (!flightmode->crash_check_enabled()) {
281
control_loss_count = 0;
282
return;
283
}
284
285
// ensure we are flying
286
if (ap.land_complete) {
287
control_loss_count = 0;
288
return;
289
}
290
291
// ensure the first control_loss event is from above the min altitude
292
if (control_loss_count == 0 && parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100)) {
293
return;
294
}
295
296
// trigger parachute release based on sink rate
297
parachute.check_sink_rate();
298
299
// check for angle error over 30 degrees
300
const float angle_error = attitude_control->get_att_error_angle_deg();
301
if (angle_error <= PARACHUTE_CHECK_ANGLE_DEVIATION_DEG) {
302
if (control_loss_count > 0) {
303
control_loss_count--;
304
}
305
return;
306
}
307
308
// increment counter
309
if (control_loss_count < (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
310
control_loss_count++;
311
}
312
313
// record baro alt if we have just started losing control
314
if (control_loss_count == 1) {
315
baro_alt_start_m = baro_alt_m;
316
317
// exit if baro altitude change indicates we are not falling
318
} else if (baro_alt_m >= baro_alt_start_m) {
319
control_loss_count = 0;
320
return;
321
322
// To-Do: add check that the vehicle is actually falling
323
324
// check if loss of control for at least 1 second
325
} else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) {
326
// reset control loss counter
327
control_loss_count = 0;
328
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL);
329
// release parachute
330
parachute_release();
331
}
332
}
333
334
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
335
void Copter::parachute_release()
336
{
337
// release parachute
338
parachute.release();
339
340
#if AP_LANDINGGEAR_ENABLED
341
// deploy landing gear
342
landinggear.set_position(AP_LandingGear::LandingGear_Deploy);
343
#endif
344
}
345
346
// parachute_manual_release - trigger the release of the parachute, after performing some checks for pilot error
347
// checks if the vehicle is landed
348
void Copter::parachute_manual_release()
349
{
350
// exit immediately if parachute is not enabled
351
if (!parachute.enabled()) {
352
return;
353
}
354
355
// do not release if vehicle is landed
356
// do not release if we are landed or below the minimum altitude above home
357
if (ap.land_complete) {
358
// warn user of reason for failure
359
gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed");
360
LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED);
361
return;
362
}
363
364
// do not release if we are landed or below the minimum altitude above home
365
if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {
366
// warn user of reason for failure
367
gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");
368
LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW);
369
return;
370
}
371
372
// if we get this far release parachute
373
parachute_release();
374
}
375
376
#endif // HAL_PARACHUTE_ENABLED
377
378