Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/failsafe.cpp
9383 views
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 (g.failsafe_pilot_input == FS_PILOT_INPUT_DISABLED) {
174
failsafe.pilot_input = false;
175
return;
176
}
177
178
if (AP_HAL::millis() < failsafe.last_pilot_input_ms + g.failsafe_pilot_input_timeout * 1000.0f) {
179
failsafe.pilot_input = false; // We've received an update from the pilot within the timeout period
180
return;
181
}
182
183
if (failsafe.pilot_input) {
184
return; // only act once
185
}
186
187
failsafe.pilot_input = true;
188
189
LOGGER_WRITE_ERROR(LogErrorSubsystem::PILOT_INPUT, LogErrorCode::FAILSAFE_OCCURRED);
190
gcs().send_text(MAV_SEVERITY_CRITICAL, "Lost manual control");
191
192
set_neutral_controls();
193
194
if(g.failsafe_pilot_input == FS_PILOT_INPUT_DISARM) {
195
arming.disarm(AP_Arming::Method::PILOT_INPUT_FAILSAFE);
196
}
197
}
198
199
// Internal pressure failsafe check
200
// Check if the internal pressure of the watertight electronics enclosure
201
// has exceeded the maximum specified by the FS_PRESS_MAX parameter
202
void Sub::failsafe_internal_pressure_check()
203
{
204
205
if (g.failsafe_pressure == FS_PRESS_DISABLED) {
206
return; // Nothing to do
207
}
208
209
uint32_t tnow = AP_HAL::millis();
210
static uint32_t last_pressure_warn_ms;
211
static uint32_t last_pressure_good_ms;
212
if (barometer.get_pressure(0) < g.failsafe_pressure_max) {
213
last_pressure_good_ms = tnow;
214
last_pressure_warn_ms = tnow;
215
failsafe.internal_pressure = false;
216
return;
217
}
218
219
// 2 seconds with no readings below threshold triggers failsafe
220
if (tnow > last_pressure_good_ms + 2000) {
221
failsafe.internal_pressure = true;
222
}
223
224
// Warn every 30 seconds
225
if (failsafe.internal_pressure && tnow > last_pressure_warn_ms + 30000) {
226
last_pressure_warn_ms = tnow;
227
gcs().send_text(MAV_SEVERITY_WARNING, "Internal pressure critical!");
228
}
229
}
230
231
// Internal temperature failsafe check
232
// Check if the internal temperature of the watertight electronics enclosure
233
// has exceeded the maximum specified by the FS_TEMP_MAX parameter
234
void Sub::failsafe_internal_temperature_check()
235
{
236
237
if (g.failsafe_temperature == FS_TEMP_DISABLED) {
238
return; // Nothing to do
239
}
240
241
uint32_t tnow = AP_HAL::millis();
242
static uint32_t last_temperature_warn_ms;
243
static uint32_t last_temperature_good_ms;
244
if (barometer.get_temperature(0) < g.failsafe_temperature_max) {
245
last_temperature_good_ms = tnow;
246
last_temperature_warn_ms = tnow;
247
failsafe.internal_temperature = false;
248
return;
249
}
250
251
// 2 seconds with no readings below threshold triggers failsafe
252
if (tnow > last_temperature_good_ms + 2000) {
253
failsafe.internal_temperature = true;
254
}
255
256
// Warn every 30 seconds
257
if (failsafe.internal_temperature && tnow > last_temperature_warn_ms + 30000) {
258
last_temperature_warn_ms = tnow;
259
gcs().send_text(MAV_SEVERITY_WARNING, "Internal temperature critical!");
260
}
261
}
262
263
// Check if we are leaking and perform appropriate action
264
void Sub::failsafe_leak_check()
265
{
266
bool status = leak_detector.get_status();
267
268
// Do nothing if we are dry, or if leak failsafe action is disabled
269
if (status == false || g.failsafe_leak == FS_LEAK_DISABLED) {
270
if (failsafe.leak) {
271
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_RESOLVED);
272
}
273
AP_Notify::flags.leak_detected = false;
274
failsafe.leak = false;
275
return;
276
}
277
278
AP_Notify::flags.leak_detected = status;
279
280
uint32_t tnow = AP_HAL::millis();
281
282
// We have a leak
283
// Always send a warning every 20 seconds
284
if (tnow > failsafe.last_leak_warn_ms + 20000) {
285
failsafe.last_leak_warn_ms = tnow;
286
gcs().send_text(MAV_SEVERITY_CRITICAL, "Leak Detected");
287
}
288
289
// Do nothing if we have already triggered the failsafe action, or if the motors are disarmed
290
if (failsafe.leak) {
291
return;
292
}
293
294
failsafe.leak = true;
295
296
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_OCCURRED);
297
298
// Handle failsafe action
299
if (failsafe.leak && g.failsafe_leak == FS_LEAK_SURFACE && motors.armed()) {
300
set_mode(Mode::Number::SURFACE, ModeReason::LEAK_FAILSAFE);
301
}
302
}
303
304
// failsafe_gcs_check - check for ground station failsafe
305
void Sub::failsafe_gcs_check()
306
{
307
// return immediately if we have never had contact with a gcs, or if gcs failsafe action is disabled
308
// 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.
309
if (!g.failsafe_gcs && g.failsafe_gcs == FS_GCS_DISABLED) {
310
return;
311
}
312
313
const uint32_t gcs_last_seen_ms = gcs().sysid_mygcs_last_seen_time_ms();
314
if (gcs_last_seen_ms == 0) {
315
// we've never seen a GCS, so we don't failsafe if we stop seeing it
316
return;
317
}
318
319
uint32_t tnow = AP_HAL::millis();
320
321
// Check if we have gotten a GCS heartbeat recently (GCS sysid must match MAV_GCS_SYSID parameter)
322
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g.failsafe_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
323
if (tnow - gcs_last_seen_ms < gcs_timeout_ms) {
324
// Log event if we are recovering from previous gcs failsafe
325
if (failsafe.gcs) {
326
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);
327
GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"GCS Failsafe Cleared");
328
}
329
failsafe.gcs = false;
330
AP_Notify::flags.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: heartbeat lost");
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
AP_Notify::flags.failsafe_gcs = true;
351
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);
352
353
// handle failsafe action
354
if (g.failsafe_gcs == FS_GCS_DISARM) {
355
arming.disarm(AP_Arming::Method::GCSFAILSAFE);
356
} else if (g.failsafe_gcs == FS_GCS_HOLD && motors.armed()) {
357
if (!set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_FAILSAFE)) {
358
arming.disarm(AP_Arming::Method::GCS_FAILSAFE_HOLDFAILED);
359
}
360
} else if (g.failsafe_gcs == FS_GCS_SURFACE && motors.armed()) {
361
if (!set_mode(Mode::Number::SURFACE, ModeReason::GCS_FAILSAFE)) {
362
arming.disarm(AP_Arming::Method::GCS_FAILSAFE_SURFACEFAILED);
363
}
364
}
365
}
366
367
#define CRASH_CHECK_TRIGGER_MS 2000 // 2 seconds inverted indicates a crash
368
#define CRASH_CHECK_ANGLE_DEVIATION_DEG 30.0f // 30 degrees beyond angle max is signal we are inverted
369
370
// Check for a crash
371
// The vehicle is considered crashed if the angle error exceeds a specified limit for more than 2 seconds
372
void Sub::failsafe_crash_check()
373
{
374
static uint32_t last_crash_check_pass_ms;
375
uint32_t tnow = AP_HAL::millis();
376
377
// return immediately if disarmed, or crash checking disabled
378
if (!motors.armed() || g.fs_crash_check == FS_CRASH_DISABLED) {
379
last_crash_check_pass_ms = tnow;
380
failsafe.crash = false;
381
return;
382
}
383
384
// return immediately if we are not in an angle stabilized flight mode
385
if (control_mode == Mode::Number::ACRO || control_mode == Mode::Number::MANUAL) {
386
last_crash_check_pass_ms = tnow;
387
failsafe.crash = false;
388
return;
389
}
390
391
// check for angle error over 30 degrees
392
const float angle_error = attitude_control.get_att_error_angle_deg();
393
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
394
last_crash_check_pass_ms = tnow;
395
failsafe.crash = false;
396
return;
397
}
398
399
if (tnow < last_crash_check_pass_ms + CRASH_CHECK_TRIGGER_MS) {
400
return;
401
}
402
403
// Conditions met, we are in failsafe
404
405
// Send warning to GCS
406
if (tnow > failsafe.last_crash_warn_ms + 20000) {
407
failsafe.last_crash_warn_ms = tnow;
408
gcs().send_text(MAV_SEVERITY_WARNING,"Crash detected");
409
}
410
411
// Only perform failsafe action once
412
if (failsafe.crash) {
413
return;
414
}
415
416
failsafe.crash = true;
417
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH);
418
419
// disarm motors
420
if (g.fs_crash_check == FS_CRASH_DISARM) {
421
arming.disarm(AP_Arming::Method::CRASH);
422
}
423
}
424
425
// executes terrain failsafe if data is missing for longer than a few seconds
426
// missing_data should be set to true if the vehicle failed to navigate because of missing data, false if navigation is proceeding successfully
427
void Sub::failsafe_terrain_check()
428
{
429
// trigger with 5 seconds of failures while in AUTO mode
430
bool valid_mode = (control_mode == Mode::Number::AUTO || control_mode == Mode::Number::GUIDED);
431
bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
432
bool trigger_event = valid_mode && timeout;
433
434
// check for clearing of event
435
if (trigger_event != failsafe.terrain) {
436
if (trigger_event) {
437
gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe terrain triggered");
438
failsafe_terrain_on_event();
439
} else {
440
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);
441
failsafe.terrain = false;
442
}
443
}
444
}
445
446
// This gets called if mission items are in ALT_ABOVE_TERRAIN frame
447
// Terrain failure occurs when terrain data is not found, or rangefinder is not enabled or healthy
448
// set terrain data status (found or not found)
449
void Sub::failsafe_terrain_set_status(bool data_ok)
450
{
451
uint32_t now = AP_HAL::millis();
452
453
// record time of first and latest failures (i.e. duration of failures)
454
if (!data_ok) {
455
failsafe.terrain_last_failure_ms = now;
456
if (failsafe.terrain_first_failure_ms == 0) {
457
failsafe.terrain_first_failure_ms = now;
458
}
459
} else {
460
// failures cleared after 0.1 seconds of persistent successes
461
if (now - failsafe.terrain_last_failure_ms > 100) {
462
failsafe.terrain_last_failure_ms = 0;
463
failsafe.terrain_first_failure_ms = 0;
464
}
465
}
466
}
467
468
// terrain failsafe action
469
void Sub::failsafe_terrain_on_event()
470
{
471
failsafe.terrain = true;
472
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);
473
474
// If rangefinder is enabled, we can recover from this failsafe
475
if (!rangefinder_state.enabled || !sub.mode_auto.auto_terrain_recover_start()) {
476
failsafe_terrain_act();
477
}
478
479
480
}
481
482
// Recovery failed, take action
483
void Sub::failsafe_terrain_act()
484
{
485
switch (g.failsafe_terrain) {
486
case FS_TERRAIN_HOLD:
487
if (!set_mode(Mode::Number::POSHOLD, ModeReason::TERRAIN_FAILSAFE)) {
488
set_mode(Mode::Number::ALT_HOLD, ModeReason::TERRAIN_FAILSAFE);
489
}
490
AP_Notify::events.failsafe_mode_change = 1;
491
break;
492
493
case FS_TERRAIN_SURFACE:
494
set_mode(Mode::Number::SURFACE, ModeReason::TERRAIN_FAILSAFE);
495
AP_Notify::events.failsafe_mode_change = 1;
496
break;
497
498
case FS_TERRAIN_DISARM:
499
default:
500
arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);
501
}
502
}
503
504
#if AP_SUB_RC_ENABLED
505
void Sub::set_failsafe_radio(bool b)
506
{
507
// only act on changes
508
// -------------------
509
if(failsafe.radio != b) {
510
511
// store the value so we don't trip the gate twice
512
// -----------------------------------------------
513
failsafe.radio = b;
514
515
if (failsafe.radio == false) {
516
// We've regained radio contact
517
// ----------------------------
518
failsafe_radio_off_event();
519
520
}else{
521
// We've lost radio contact
522
// ------------------------
523
failsafe_radio_on_event();
524
}
525
526
// update AP_Notify
527
AP_Notify::flags.failsafe_radio = b;
528
}
529
}
530
531
// failsafe_radio_on_event - RC contact lost
532
void Sub::failsafe_radio_on_event()
533
{
534
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);
535
gcs().send_text(MAV_SEVERITY_WARNING, "RC Failsafe");
536
switch(g.failsafe_throttle) {
537
case FS_THR_SURFACE:
538
set_mode(Mode::Number::SURFACE, ModeReason::RADIO_FAILSAFE);
539
break;
540
case FS_THR_WARN:
541
set_neutral_controls();
542
break;
543
case FS_THR_DISABLED:
544
break;
545
}
546
}
547
548
// failsafe_radio_off event- respond to radio contact being regained
549
void Sub::failsafe_radio_off_event()
550
{
551
// no need to do anything except log the error as resolved
552
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
553
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);
554
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared");
555
}
556
#endif
557
558