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/ArduSub/failsafe.cpp
Views: 1798
1
#include "Sub.h"
2
3
/*
4
* failsafe.cpp
5
* Failsafe checks and actions
6
*/
7
8
static bool failsafe_enabled = false;
9
static uint16_t failsafe_last_ticks;
10
static uint32_t failsafe_last_timestamp;
11
static bool in_failsafe;
12
13
// Enable mainloop lockup failsafe
14
void Sub::mainloop_failsafe_enable()
15
{
16
failsafe_enabled = true;
17
failsafe_last_timestamp = AP_HAL::micros();
18
}
19
20
// Disable mainloop lockup failsafe
21
// Used when we know we are going to delay the mainloop significantly.
22
void Sub::mainloop_failsafe_disable()
23
{
24
failsafe_enabled = false;
25
}
26
27
// This function is called from the core timer interrupt at 1kHz.
28
// This checks that the mainloop is running, and has not locked up.
29
void Sub::mainloop_failsafe_check()
30
{
31
uint32_t tnow = AP_HAL::micros();
32
33
const uint16_t ticks = scheduler.ticks();
34
if (ticks != failsafe_last_ticks) {
35
// the main loop is running, all is OK
36
failsafe_last_ticks = ticks;
37
failsafe_last_timestamp = tnow;
38
if (in_failsafe) {
39
in_failsafe = false;
40
LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_RESOLVED);
41
}
42
return;
43
}
44
45
if (!in_failsafe && failsafe_enabled && tnow - failsafe_last_timestamp > 2000000) {
46
// motors are running but we have gone 2 second since the
47
// main loop ran. That means we're in trouble and should
48
// disarm the motors.
49
in_failsafe = true;
50
// reduce motors to minimum (we do not immediately disarm because we want to log the failure)
51
if (motors.armed()) {
52
motors.output_min();
53
}
54
LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_OCCURRED);
55
}
56
57
if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) {
58
// disarm motors every second
59
failsafe_last_timestamp = tnow;
60
if (motors.armed()) {
61
motors.armed(false);
62
motors.output();
63
}
64
}
65
}
66
67
void Sub::failsafe_sensors_check()
68
{
69
if (!ap.depth_sensor_present) {
70
return;
71
}
72
73
// We need a depth sensor to do any sort of auto z control
74
if (sensor_health.depth) {
75
if (failsafe.sensor_health) {
76
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::ERROR_RESOLVED);
77
failsafe.sensor_health = false;
78
}
79
return;
80
}
81
82
// only report once
83
if (failsafe.sensor_health) {
84
return;
85
}
86
87
failsafe.sensor_health = true;
88
gcs().send_text(MAV_SEVERITY_CRITICAL, "Depth sensor error!");
89
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::BAD_DEPTH);
90
91
if (control_mode == Mode::Number::ALT_HOLD || control_mode == Mode::Number::SURFACE || sub.flightmode->requires_GPS()) {
92
// This should always succeed
93
if (!set_mode(Mode::Number::MANUAL, ModeReason::BAD_DEPTH)) {
94
// We should never get here
95
arming.disarm(AP_Arming::Method::BADFLOWOFCONTROL);
96
}
97
}
98
}
99
100
void Sub::failsafe_ekf_check()
101
{
102
static uint32_t last_ekf_good_ms = 0;
103
104
if (g.fs_ekf_action == FS_EKF_ACTION_DISABLED) {
105
last_ekf_good_ms = AP_HAL::millis();
106
failsafe.ekf = false;
107
AP_Notify::flags.ekf_bad = false;
108
return;
109
}
110
111
float posVar, hgtVar, tasVar;
112
Vector3f magVar;
113
float compass_variance;
114
float vel_variance;
115
ahrs.get_variances(vel_variance, posVar, hgtVar, magVar, tasVar);
116
compass_variance = magVar.length();
117
118
if (compass_variance < g.fs_ekf_thresh && vel_variance < g.fs_ekf_thresh) {
119
last_ekf_good_ms = AP_HAL::millis();
120
failsafe.ekf = false;
121
AP_Notify::flags.ekf_bad = false;
122
return;
123
}
124
125
// Bad EKF for 2 solid seconds triggers failsafe
126
if (AP_HAL::millis() < last_ekf_good_ms + 2000) {
127
failsafe.ekf = false;
128
AP_Notify::flags.ekf_bad = false;
129
return;
130
}
131
132
// Only trigger failsafe once
133
if (failsafe.ekf) {
134
return;
135
}
136
137
failsafe.ekf = true;
138
AP_Notify::flags.ekf_bad = true;
139
140
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
141
142
if (AP_HAL::millis() > failsafe.last_ekf_warn_ms + 20000) {
143
failsafe.last_ekf_warn_ms = AP_HAL::millis();
144
gcs().send_text(MAV_SEVERITY_WARNING, "EKF bad");
145
}
146
147
if (g.fs_ekf_action == FS_EKF_ACTION_DISARM) {
148
arming.disarm(AP_Arming::Method::EKFFAILSAFE);
149
}
150
}
151
152
// Battery failsafe handler
153
void Sub::handle_battery_failsafe(const char* type_str, const int8_t action)
154
{
155
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);
156
157
switch((Failsafe_Action)action) {
158
case Failsafe_Action_Surface:
159
set_mode(Mode::Number::SURFACE, ModeReason::BATTERY_FAILSAFE);
160
break;
161
case Failsafe_Action_Disarm:
162
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
163
break;
164
case Failsafe_Action_Warn:
165
case Failsafe_Action_None:
166
break;
167
}
168
}
169
170
// Make sure that we are receiving pilot input at an appropriate interval
171
void Sub::failsafe_pilot_input_check()
172
{
173
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
174
if (g.failsafe_pilot_input == FS_PILOT_INPUT_DISABLED) {
175
failsafe.pilot_input = false;
176
return;
177
}
178
179
if (AP_HAL::millis() < failsafe.last_pilot_input_ms + g.failsafe_pilot_input_timeout * 1000.0f) {
180
failsafe.pilot_input = false; // We've received an update from the pilot within the timeout period
181
return;
182
}
183
184
if (failsafe.pilot_input) {
185
return; // only act once
186
}
187
188
failsafe.pilot_input = true;
189
190
LOGGER_WRITE_ERROR(LogErrorSubsystem::PILOT_INPUT, LogErrorCode::FAILSAFE_OCCURRED);
191
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lost manual control");
192
193
set_neutral_controls();
194
195
if(g.failsafe_pilot_input == FS_PILOT_INPUT_DISARM) {
196
arming.disarm(AP_Arming::Method::PILOT_INPUT_FAILSAFE);
197
}
198
#endif
199
}
200
201
// Internal pressure failsafe check
202
// Check if the internal pressure of the watertight electronics enclosure
203
// has exceeded the maximum specified by the FS_PRESS_MAX parameter
204
void Sub::failsafe_internal_pressure_check()
205
{
206
207
if (g.failsafe_pressure == FS_PRESS_DISABLED) {
208
return; // Nothing to do
209
}
210
211
uint32_t tnow = AP_HAL::millis();
212
static uint32_t last_pressure_warn_ms;
213
static uint32_t last_pressure_good_ms;
214
if (barometer.get_pressure(0) < g.failsafe_pressure_max) {
215
last_pressure_good_ms = tnow;
216
last_pressure_warn_ms = tnow;
217
failsafe.internal_pressure = false;
218
return;
219
}
220
221
// 2 seconds with no readings below threshold triggers failsafe
222
if (tnow > last_pressure_good_ms + 2000) {
223
failsafe.internal_pressure = true;
224
}
225
226
// Warn every 30 seconds
227
if (failsafe.internal_pressure && tnow > last_pressure_warn_ms + 30000) {
228
last_pressure_warn_ms = tnow;
229
gcs().send_text(MAV_SEVERITY_WARNING, "Internal pressure critical!");
230
}
231
}
232
233
// Internal temperature failsafe check
234
// Check if the internal temperature of the watertight electronics enclosure
235
// has exceeded the maximum specified by the FS_TEMP_MAX parameter
236
void Sub::failsafe_internal_temperature_check()
237
{
238
239
if (g.failsafe_temperature == FS_TEMP_DISABLED) {
240
return; // Nothing to do
241
}
242
243
uint32_t tnow = AP_HAL::millis();
244
static uint32_t last_temperature_warn_ms;
245
static uint32_t last_temperature_good_ms;
246
if (barometer.get_temperature(0) < g.failsafe_temperature_max) {
247
last_temperature_good_ms = tnow;
248
last_temperature_warn_ms = tnow;
249
failsafe.internal_temperature = false;
250
return;
251
}
252
253
// 2 seconds with no readings below threshold triggers failsafe
254
if (tnow > last_temperature_good_ms + 2000) {
255
failsafe.internal_temperature = true;
256
}
257
258
// Warn every 30 seconds
259
if (failsafe.internal_temperature && tnow > last_temperature_warn_ms + 30000) {
260
last_temperature_warn_ms = tnow;
261
gcs().send_text(MAV_SEVERITY_WARNING, "Internal temperature critical!");
262
}
263
}
264
265
// Check if we are leaking and perform appropriate action
266
void Sub::failsafe_leak_check()
267
{
268
bool status = leak_detector.get_status();
269
270
// Do nothing if we are dry, or if leak failsafe action is disabled
271
if (status == false || g.failsafe_leak == FS_LEAK_DISABLED) {
272
if (failsafe.leak) {
273
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_RESOLVED);
274
}
275
AP_Notify::flags.leak_detected = false;
276
failsafe.leak = false;
277
return;
278
}
279
280
AP_Notify::flags.leak_detected = status;
281
282
uint32_t tnow = AP_HAL::millis();
283
284
// We have a leak
285
// Always send a warning every 20 seconds
286
if (tnow > failsafe.last_leak_warn_ms + 20000) {
287
failsafe.last_leak_warn_ms = tnow;
288
gcs().send_text(MAV_SEVERITY_CRITICAL, "Leak Detected");
289
}
290
291
// Do nothing if we have already triggered the failsafe action, or if the motors are disarmed
292
if (failsafe.leak) {
293
return;
294
}
295
296
failsafe.leak = true;
297
298
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_OCCURRED);
299
300
// Handle failsafe action
301
if (failsafe.leak && g.failsafe_leak == FS_LEAK_SURFACE && motors.armed()) {
302
set_mode(Mode::Number::SURFACE, ModeReason::LEAK_FAILSAFE);
303
}
304
}
305
306
// failsafe_gcs_check - check for ground station failsafe
307
void Sub::failsafe_gcs_check()
308
{
309
// return immediately if we have never had contact with a gcs, or if gcs failsafe action is disabled
310
// this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state.
311
if (!g.failsafe_gcs && g.failsafe_gcs == FS_GCS_DISABLED) {
312
return;
313
}
314
315
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
316
if (gcs_last_seen_ms == 0) {
317
// we've never seen a GCS, so we don't failsafe if we stop seeing it
318
return;
319
}
320
321
uint32_t tnow = AP_HAL::millis();
322
323
// Check if we have gotten a GCS heartbeat recently (GCS sysid must match SYSID_MYGCS parameter)
324
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g.failsafe_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
325
if (tnow - gcs_last_seen_ms < gcs_timeout_ms) {
326
// Log event if we are recovering from previous gcs failsafe
327
if (failsafe.gcs) {
328
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);
329
}
330
failsafe.gcs = false;
331
return;
332
}
333
334
//////////////////////////////
335
// GCS heartbeat has timed out
336
//////////////////////////////
337
338
// Send a warning every 30 seconds
339
if (tnow - failsafe.last_gcs_warn_ms > 30000) {
340
failsafe.last_gcs_warn_ms = tnow;
341
gcs().send_text(MAV_SEVERITY_WARNING, "MYGCS: %u, heartbeat lost", g.sysid_my_gcs.get());
342
}
343
344
// do nothing if we have already triggered the failsafe action, or if the motors are disarmed
345
if (failsafe.gcs || !motors.armed()) {
346
return;
347
}
348
349
failsafe.gcs = true;
350
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);
351
352
// handle failsafe action
353
if (g.failsafe_gcs == FS_GCS_DISARM) {
354
arming.disarm(AP_Arming::Method::GCSFAILSAFE);
355
} else if (g.failsafe_gcs == FS_GCS_HOLD && motors.armed()) {
356
if (!set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_FAILSAFE)) {
357
arming.disarm(AP_Arming::Method::GCS_FAILSAFE_HOLDFAILED);
358
}
359
} else if (g.failsafe_gcs == FS_GCS_SURFACE && motors.armed()) {
360
if (!set_mode(Mode::Number::SURFACE, ModeReason::GCS_FAILSAFE)) {
361
arming.disarm(AP_Arming::Method::GCS_FAILSAFE_SURFACEFAILED);
362
}
363
}
364
}
365
366
#define CRASH_CHECK_TRIGGER_MS 2000 // 2 seconds inverted indicates a crash
367
#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond angle max is signal we are inverted
368
369
// Check for a crash
370
// The vehicle is considered crashed if the angle error exceeds a specified limit for more than 2 seconds
371
void Sub::failsafe_crash_check()
372
{
373
static uint32_t last_crash_check_pass_ms;
374
uint32_t tnow = AP_HAL::millis();
375
376
// return immediately if disarmed, or crash checking disabled
377
if (!motors.armed() || g.fs_crash_check == FS_CRASH_DISABLED) {
378
last_crash_check_pass_ms = tnow;
379
failsafe.crash = false;
380
return;
381
}
382
383
// return immediately if we are not in an angle stabilized flight mode
384
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::MANUAL) {
385
last_crash_check_pass_ms = tnow;
386
failsafe.crash = false;
387
return;
388
}
389
390
// check for angle error over 30 degrees
391
const float angle_error = attitude_control.get_att_error_angle_deg();
392
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
393
last_crash_check_pass_ms = tnow;
394
failsafe.crash = false;
395
return;
396
}
397
398
if (tnow < last_crash_check_pass_ms + CRASH_CHECK_TRIGGER_MS) {
399
return;
400
}
401
402
// Conditions met, we are in failsafe
403
404
// Send warning to GCS
405
if (tnow > failsafe.last_crash_warn_ms + 20000) {
406
failsafe.last_crash_warn_ms = tnow;
407
gcs().send_text(MAV_SEVERITY_WARNING,"Crash detected");
408
}
409
410
// Only perform failsafe action once
411
if (failsafe.crash) {
412
return;
413
}
414
415
failsafe.crash = true;
416
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
417
418
// disarm motors
419
if (g.fs_crash_check == FS_CRASH_DISARM) {
420
arming.disarm(AP_Arming::Method::CRASH);
421
}
422
}
423
424
// executes terrain failsafe if data is missing for longer than a few seconds
425
// missing_data should be set to true if the vehicle failed to navigate because of missing data, false if navigation is proceeding successfully
426
void Sub::failsafe_terrain_check()
427
{
428
// trigger with 5 seconds of failures while in AUTO mode
429
bool valid_mode = (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::GUIDED);
430
bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
431
bool trigger_event = valid_mode && timeout;
432
433
// check for clearing of event
434
if (trigger_event != failsafe.terrain) {
435
if (trigger_event) {
436
gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe terrain triggered");
437
failsafe_terrain_on_event();
438
} else {
439
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);
440
failsafe.terrain = false;
441
}
442
}
443
}
444
445
// This gets called if mission items are in ALT_ABOVE_TERRAIN frame
446
// Terrain failure occurs when terrain data is not found, or rangefinder is not enabled or healthy
447
// set terrain data status (found or not found)
448
void Sub::failsafe_terrain_set_status(bool data_ok)
449
{
450
uint32_t now = AP_HAL::millis();
451
452
// record time of first and latest failures (i.e. duration of failures)
453
if (!data_ok) {
454
failsafe.terrain_last_failure_ms = now;
455
if (failsafe.terrain_first_failure_ms == 0) {
456
failsafe.terrain_first_failure_ms = now;
457
}
458
} else {
459
// failures cleared after 0.1 seconds of persistent successes
460
if (now - failsafe.terrain_last_failure_ms > 100) {
461
failsafe.terrain_last_failure_ms = 0;
462
failsafe.terrain_first_failure_ms = 0;
463
}
464
}
465
}
466
467
// terrain failsafe action
468
void Sub::failsafe_terrain_on_event()
469
{
470
failsafe.terrain = true;
471
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);
472
473
// If rangefinder is enabled, we can recover from this failsafe
474
if (!rangefinder_state.enabled || !sub.mode_auto.auto_terrain_recover_start()) {
475
failsafe_terrain_act();
476
}
477
478
479
}
480
481
// Recovery failed, take action
482
void Sub::failsafe_terrain_act()
483
{
484
switch (g.failsafe_terrain) {
485
case FS_TERRAIN_HOLD:
486
if (!set_mode(Mode::Number::POSHOLD, ModeReason::TERRAIN_FAILSAFE)) {
487
set_mode(Mode::Number::ALT_HOLD, ModeReason::TERRAIN_FAILSAFE);
488
}
489
AP_Notify::events.failsafe_mode_change = 1;
490
break;
491
492
case FS_TERRAIN_SURFACE:
493
set_mode(Mode::Number::SURFACE, ModeReason::TERRAIN_FAILSAFE);
494
AP_Notify::events.failsafe_mode_change = 1;
495
break;
496
497
case FS_TERRAIN_DISARM:
498
default:
499
arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);
500
}
501
}
502
503