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/events.cpp
Views: 1798
1
#include "Copter.h"
2
3
/*
4
* This event will be called when the failsafe changes
5
* boolean failsafe reflects the current state
6
*/
7
8
bool Copter::failsafe_option(FailsafeOption opt) const
9
{
10
return (g2.fs_options & (uint32_t)opt);
11
}
12
13
void Copter::failsafe_radio_on_event()
14
{
15
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED);
16
17
// set desired action based on FS_THR_ENABLE parameter
18
FailsafeAction desired_action;
19
switch (g.failsafe_throttle) {
20
case FS_THR_DISABLED:
21
desired_action = FailsafeAction::NONE;
22
break;
23
case FS_THR_ENABLED_ALWAYS_RTL:
24
case FS_THR_ENABLED_CONTINUE_MISSION:
25
desired_action = FailsafeAction::RTL;
26
break;
27
case FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_RTL:
28
desired_action = FailsafeAction::SMARTRTL;
29
break;
30
case FS_THR_ENABLED_ALWAYS_SMARTRTL_OR_LAND:
31
desired_action = FailsafeAction::SMARTRTL_LAND;
32
break;
33
case FS_THR_ENABLED_ALWAYS_LAND:
34
desired_action = FailsafeAction::LAND;
35
break;
36
case FS_THR_ENABLED_AUTO_RTL_OR_RTL:
37
desired_action = FailsafeAction::AUTO_DO_LAND_START;
38
break;
39
case FS_THR_ENABLED_BRAKE_OR_LAND:
40
desired_action = FailsafeAction::BRAKE_LAND;
41
break;
42
default:
43
desired_action = FailsafeAction::LAND;
44
}
45
46
// Conditions to deviate from FS_THR_ENABLE selection and send specific GCS warning
47
if (should_disarm_on_failsafe()) {
48
// should immediately disarm when we're on the ground
49
announce_failsafe("Radio", "Disarming");
50
arming.disarm(AP_Arming::Method::RADIOFAILSAFE);
51
desired_action = FailsafeAction::NONE;
52
53
} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {
54
// Allow landing to continue when battery failsafe requires it (not a user option)
55
announce_failsafe("Radio + Battery", "Continuing Landing");
56
desired_action = FailsafeAction::LAND;
57
58
} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {
59
// Allow landing to continue when FS_OPTIONS is set to continue landing
60
announce_failsafe("Radio", "Continuing Landing");
61
desired_action = FailsafeAction::LAND;
62
63
} else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::RC_CONTINUE_IF_AUTO)) {
64
// Allow mission to continue when FS_OPTIONS is set to continue mission
65
announce_failsafe("Radio", "Continuing Auto");
66
desired_action = FailsafeAction::NONE;
67
68
} else if ((flightmode->in_guided_mode()) && failsafe_option(FailsafeOption::RC_CONTINUE_IF_GUIDED)) {
69
// Allow guided mode to continue when FS_OPTIONS is set to continue in guided mode
70
announce_failsafe("Radio", "Continuing Guided Mode");
71
desired_action = FailsafeAction::NONE;
72
73
} else {
74
announce_failsafe("Radio");
75
}
76
77
// Call the failsafe action handler
78
do_failsafe_action(desired_action, ModeReason::RADIO_FAILSAFE);
79
}
80
81
// failsafe_off_event - respond to radio contact being regained
82
void Copter::failsafe_radio_off_event()
83
{
84
// no need to do anything except log the error as resolved
85
// user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode
86
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED);
87
gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared");
88
}
89
90
void Copter::announce_failsafe(const char *type, const char *action_undertaken)
91
{
92
if (action_undertaken != nullptr) {
93
gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe - %s", type, action_undertaken);
94
} else {
95
gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe", type);
96
}
97
}
98
99
void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
100
{
101
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED);
102
103
FailsafeAction desired_action = (FailsafeAction)action;
104
105
// Conditions to deviate from BATT_FS_XXX_ACT parameter setting
106
if (should_disarm_on_failsafe()) {
107
// should immediately disarm when we're on the ground
108
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
109
desired_action = FailsafeAction::NONE;
110
announce_failsafe("Battery", "Disarming");
111
112
} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING) && desired_action != FailsafeAction::NONE) {
113
// Allow landing to continue when FS_OPTIONS is set to continue when landing
114
desired_action = FailsafeAction::LAND;
115
announce_failsafe("Battery", "Continuing Landing");
116
} else {
117
announce_failsafe("Battery");
118
}
119
120
// Battery FS options already use the Failsafe_Options enum. So use them directly.
121
do_failsafe_action(desired_action, ModeReason::BATTERY_FAILSAFE);
122
123
}
124
125
// failsafe_gcs_check - check for ground station failsafe
126
void Copter::failsafe_gcs_check()
127
{
128
// Bypass GCS failsafe checks if disabled or GCS never connected
129
if (g.failsafe_gcs == FS_GCS_DISABLED) {
130
return;
131
}
132
133
const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();
134
if (gcs_last_seen_ms == 0) {
135
return;
136
}
137
138
// calc time since last gcs update
139
// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs
140
const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;
141
const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));
142
143
// Determine which event to trigger
144
if (last_gcs_update_ms < gcs_timeout_ms && failsafe.gcs) {
145
// Recovery from a GCS failsafe
146
set_failsafe_gcs(false);
147
failsafe_gcs_off_event();
148
149
} else if (last_gcs_update_ms < gcs_timeout_ms && !failsafe.gcs) {
150
// No problem, do nothing
151
152
} else if (last_gcs_update_ms > gcs_timeout_ms && failsafe.gcs) {
153
// Already in failsafe, do nothing
154
155
} else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) {
156
// New GCS failsafe event, trigger events
157
set_failsafe_gcs(true);
158
failsafe_gcs_on_event();
159
}
160
}
161
162
// failsafe_gcs_on_event - actions to take when GCS contact is lost
163
void Copter::failsafe_gcs_on_event(void)
164
{
165
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED);
166
RC_Channels::clear_overrides();
167
168
// convert the desired failsafe response to the FailsafeAction enum
169
FailsafeAction desired_action;
170
switch (g.failsafe_gcs) {
171
case FS_GCS_DISABLED:
172
desired_action = FailsafeAction::NONE;
173
break;
174
case FS_GCS_ENABLED_ALWAYS_RTL:
175
case FS_GCS_ENABLED_CONTINUE_MISSION:
176
desired_action = FailsafeAction::RTL;
177
break;
178
case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL:
179
desired_action = FailsafeAction::SMARTRTL;
180
break;
181
case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND:
182
desired_action = FailsafeAction::SMARTRTL_LAND;
183
break;
184
case FS_GCS_ENABLED_ALWAYS_LAND:
185
desired_action = FailsafeAction::LAND;
186
break;
187
case FS_GCS_ENABLED_AUTO_RTL_OR_RTL:
188
desired_action = FailsafeAction::AUTO_DO_LAND_START;
189
break;
190
case FS_GCS_ENABLED_BRAKE_OR_LAND:
191
desired_action = FailsafeAction::BRAKE_LAND;
192
break;
193
default: // if an invalid parameter value is set, the fallback is RTL
194
desired_action = FailsafeAction::RTL;
195
}
196
197
// Conditions to deviate from FS_GCS_ENABLE parameter setting
198
if (!motors->armed()) {
199
desired_action = FailsafeAction::NONE;
200
announce_failsafe("GCS");
201
202
} else if (should_disarm_on_failsafe()) {
203
// should immediately disarm when we're on the ground
204
arming.disarm(AP_Arming::Method::GCSFAILSAFE);
205
desired_action = FailsafeAction::NONE;
206
announce_failsafe("GCS", "Disarming");
207
208
} else if (flightmode->is_landing() && ((battery.has_failsafed() && battery.get_highest_failsafe_priority() <= FAILSAFE_LAND_PRIORITY))) {
209
// Allow landing to continue when battery failsafe requires it (not a user option)
210
announce_failsafe("GCS + Battery", "Continuing Landing");
211
desired_action = FailsafeAction::LAND;
212
213
} else if (flightmode->is_landing() && failsafe_option(FailsafeOption::CONTINUE_IF_LANDING)) {
214
// Allow landing to continue when FS_OPTIONS is set to continue landing
215
announce_failsafe("GCS", "Continuing Landing");
216
desired_action = FailsafeAction::LAND;
217
218
} else if (flightmode->mode_number() == Mode::Number::AUTO && failsafe_option(FailsafeOption::GCS_CONTINUE_IF_AUTO)) {
219
// Allow mission to continue when FS_OPTIONS is set to continue mission
220
announce_failsafe("GCS", "Continuing Auto Mode");
221
desired_action = FailsafeAction::NONE;
222
223
} else if (failsafe_option(FailsafeOption::GCS_CONTINUE_IF_PILOT_CONTROL) && !flightmode->is_autopilot()) {
224
// should continue when in a pilot controlled mode because FS_OPTIONS is set to continue in pilot controlled modes
225
announce_failsafe("GCS", "Continuing Pilot Control");
226
desired_action = FailsafeAction::NONE;
227
} else {
228
announce_failsafe("GCS");
229
}
230
231
// Call the failsafe action handler
232
do_failsafe_action(desired_action, ModeReason::GCS_FAILSAFE);
233
}
234
235
// failsafe_gcs_off_event - actions to take when GCS contact is restored
236
void Copter::failsafe_gcs_off_event(void)
237
{
238
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Cleared");
239
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED);
240
}
241
242
// executes terrain failsafe if data is missing for longer than a few seconds
243
void Copter::failsafe_terrain_check()
244
{
245
// trigger within <n> milliseconds of failures while in various modes
246
bool timeout = (failsafe.terrain_last_failure_ms - failsafe.terrain_first_failure_ms) > FS_TERRAIN_TIMEOUT_MS;
247
bool trigger_event = timeout && flightmode->requires_terrain_failsafe();
248
249
// check for clearing of event
250
if (trigger_event != failsafe.terrain) {
251
if (trigger_event) {
252
failsafe_terrain_on_event();
253
} else {
254
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED);
255
failsafe.terrain = false;
256
}
257
}
258
}
259
260
// set terrain data status (found or not found)
261
void Copter::failsafe_terrain_set_status(bool data_ok)
262
{
263
uint32_t now = millis();
264
265
// record time of first and latest failures (i.e. duration of failures)
266
if (!data_ok) {
267
failsafe.terrain_last_failure_ms = now;
268
if (failsafe.terrain_first_failure_ms == 0) {
269
failsafe.terrain_first_failure_ms = now;
270
}
271
} else {
272
// failures cleared after 0.1 seconds of persistent successes
273
if (now - failsafe.terrain_last_failure_ms > 100) {
274
failsafe.terrain_last_failure_ms = 0;
275
failsafe.terrain_first_failure_ms = 0;
276
}
277
}
278
}
279
280
// terrain failsafe action
281
void Copter::failsafe_terrain_on_event()
282
{
283
failsafe.terrain = true;
284
gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing");
285
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);
286
287
if (should_disarm_on_failsafe()) {
288
arming.disarm(AP_Arming::Method::TERRAINFAILSAFE);
289
#if MODE_RTL_ENABLED
290
} else if (flightmode->mode_number() == Mode::Number::RTL) {
291
mode_rtl.restart_without_terrain();
292
#endif
293
} else {
294
set_mode_RTL_or_land_with_pause(ModeReason::TERRAIN_FAILSAFE);
295
}
296
}
297
298
// check for gps glitch failsafe
299
void Copter::gpsglitch_check()
300
{
301
// get filter status
302
nav_filter_status filt_status = inertial_nav.get_filter_status();
303
bool gps_glitching = filt_status.flags.gps_glitching;
304
305
// log start or stop of gps glitch. AP_Notify update is handled from within AP_AHRS
306
if (ap.gps_glitching != gps_glitching) {
307
ap.gps_glitching = gps_glitching;
308
if (gps_glitching) {
309
LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);
310
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch or Compass error");
311
} else {
312
LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);
313
gcs().send_text(MAV_SEVERITY_CRITICAL,"Glitch cleared");
314
}
315
}
316
}
317
318
// dead reckoning alert and failsafe
319
void Copter::failsafe_deadreckon_check()
320
{
321
// update dead reckoning state
322
const char* dr_prefix_str = "Dead Reckoning";
323
324
// get EKF filter status
325
bool ekf_dead_reckoning = inertial_nav.get_filter_status().flags.dead_reckoning;
326
327
// alert user to start or stop of dead reckoning
328
const uint32_t now_ms = AP_HAL::millis();
329
if (dead_reckoning.active != ekf_dead_reckoning) {
330
dead_reckoning.active = ekf_dead_reckoning;
331
if (dead_reckoning.active) {
332
dead_reckoning.start_ms = now_ms;
333
gcs().send_text(MAV_SEVERITY_CRITICAL,"%s started", dr_prefix_str);
334
} else {
335
dead_reckoning.start_ms = 0;
336
dead_reckoning.timeout = false;
337
gcs().send_text(MAV_SEVERITY_CRITICAL,"%s stopped", dr_prefix_str);
338
}
339
}
340
341
// check for timeout
342
if (dead_reckoning.active && !dead_reckoning.timeout) {
343
const uint32_t dr_timeout_ms = uint32_t(constrain_float(g2.failsafe_dr_timeout * 1000.0f, 0.0f, UINT32_MAX));
344
if (now_ms - dead_reckoning.start_ms > dr_timeout_ms) {
345
dead_reckoning.timeout = true;
346
gcs().send_text(MAV_SEVERITY_CRITICAL,"%s timeout", dr_prefix_str);
347
}
348
}
349
350
// exit immediately if deadreckon failsafe is disabled
351
if (g2.failsafe_dr_enable <= 0) {
352
failsafe.deadreckon = false;
353
return;
354
}
355
356
// check for failsafe action
357
if (failsafe.deadreckon != ekf_dead_reckoning) {
358
failsafe.deadreckon = ekf_dead_reckoning;
359
360
// only take action in modes requiring position estimate
361
if (failsafe.deadreckon && copter.flightmode->requires_GPS()) {
362
363
// log error
364
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED);
365
366
// immediately disarm while landed
367
if (should_disarm_on_failsafe()) {
368
arming.disarm(AP_Arming::Method::DEADRECKON_FAILSAFE);
369
return;
370
}
371
372
// take user specified action
373
do_failsafe_action((FailsafeAction)g2.failsafe_dr_enable.get(), ModeReason::DEADRECKON_FAILSAFE);
374
}
375
}
376
}
377
378
// set_mode_RTL_or_land_with_pause - sets mode to RTL if possible or LAND with 4 second delay before descent starts
379
// this is always called from a failsafe so we trigger notification to pilot
380
void Copter::set_mode_RTL_or_land_with_pause(ModeReason reason)
381
{
382
#if MODE_RTL_ENABLED
383
// attempt to switch to RTL, if this fails then switch to Land
384
if (set_mode(Mode::Number::RTL, reason)) {
385
AP_Notify::events.failsafe_mode_change = 1;
386
return;
387
}
388
#endif
389
// set mode to land will trigger mode change notification to pilot
390
set_mode_land_with_pause(reason);
391
}
392
393
// set_mode_SmartRTL_or_land_with_pause - sets mode to SMART_RTL if possible or LAND with 4 second delay before descent starts
394
// this is always called from a failsafe so we trigger notification to pilot
395
void Copter::set_mode_SmartRTL_or_land_with_pause(ModeReason reason)
396
{
397
#if MODE_SMARTRTL_ENABLED
398
// attempt to switch to SMART_RTL, if this failed then switch to Land
399
if (set_mode(Mode::Number::SMART_RTL, reason)) {
400
AP_Notify::events.failsafe_mode_change = 1;
401
return;
402
}
403
#endif
404
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Using Land Mode");
405
set_mode_land_with_pause(reason);
406
}
407
408
// set_mode_SmartRTL_or_RTL - sets mode to SMART_RTL if possible or RTL if possible or LAND with 4 second delay before descent starts
409
// this is always called from a failsafe so we trigger notification to pilot
410
void Copter::set_mode_SmartRTL_or_RTL(ModeReason reason)
411
{
412
#if MODE_SMARTRTL_ENABLED
413
// attempt to switch to SmartRTL, if this failed then attempt to RTL
414
// if that fails, then land
415
if (set_mode(Mode::Number::SMART_RTL, reason)) {
416
AP_Notify::events.failsafe_mode_change = 1;
417
return;
418
}
419
#endif
420
gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL Unavailable, Trying RTL Mode");
421
set_mode_RTL_or_land_with_pause(reason);
422
}
423
424
// Sets mode to Auto and jumps to DO_LAND_START, as set with AUTO_RTL param
425
// This can come from failsafe or RC option
426
void Copter::set_mode_auto_do_land_start_or_RTL(ModeReason reason)
427
{
428
#if MODE_AUTO_ENABLED
429
if (set_mode(Mode::Number::AUTO_RTL, reason)) {
430
AP_Notify::events.failsafe_mode_change = 1;
431
return;
432
}
433
#endif
434
435
gcs().send_text(MAV_SEVERITY_WARNING, "Trying RTL Mode");
436
set_mode_RTL_or_land_with_pause(reason);
437
}
438
439
// Sets mode to Brake or LAND with 4 second delay before descent starts
440
// This can come from failsafe or RC option
441
void Copter::set_mode_brake_or_land_with_pause(ModeReason reason)
442
{
443
#if MODE_BRAKE_ENABLED
444
if (set_mode(Mode::Number::BRAKE, reason)) {
445
AP_Notify::events.failsafe_mode_change = 1;
446
return;
447
}
448
#endif
449
450
gcs().send_text(MAV_SEVERITY_WARNING, "Trying Land Mode");
451
set_mode_land_with_pause(reason);
452
}
453
454
bool Copter::should_disarm_on_failsafe() {
455
if (ap.in_arming_delay) {
456
return true;
457
}
458
459
switch (flightmode->mode_number()) {
460
case Mode::Number::STABILIZE:
461
case Mode::Number::ACRO:
462
// if throttle is zero OR vehicle is landed disarm motors
463
return ap.throttle_zero || ap.land_complete;
464
case Mode::Number::AUTO:
465
case Mode::Number::AUTO_RTL:
466
// if mission has not started AND vehicle is landed, disarm motors
467
return !ap.auto_armed && ap.land_complete;
468
default:
469
// used for AltHold, Guided, Loiter, RTL, Circle, Drift, Sport, Flip, Autotune, PosHold
470
// if landed disarm
471
return ap.land_complete;
472
}
473
}
474
475
476
void Copter::do_failsafe_action(FailsafeAction action, ModeReason reason){
477
478
// Execute the specified desired_action
479
switch (action) {
480
case FailsafeAction::NONE:
481
return;
482
case FailsafeAction::LAND:
483
set_mode_land_with_pause(reason);
484
break;
485
case FailsafeAction::RTL:
486
set_mode_RTL_or_land_with_pause(reason);
487
break;
488
case FailsafeAction::SMARTRTL:
489
set_mode_SmartRTL_or_RTL(reason);
490
break;
491
case FailsafeAction::SMARTRTL_LAND:
492
set_mode_SmartRTL_or_land_with_pause(reason);
493
break;
494
case FailsafeAction::TERMINATE: {
495
#if AP_COPTER_ADVANCED_FAILSAFE_ENABLED
496
g2.afs.gcs_terminate(true, "Failsafe");
497
#else
498
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);
499
#endif
500
break;
501
}
502
case FailsafeAction::AUTO_DO_LAND_START:
503
set_mode_auto_do_land_start_or_RTL(reason);
504
break;
505
case FailsafeAction::BRAKE_LAND:
506
set_mode_brake_or_land_with_pause(reason);
507
break;
508
}
509
510
#if AP_GRIPPER_ENABLED
511
if (failsafe_option(FailsafeOption::RELEASE_GRIPPER)) {
512
gripper.release();
513
}
514
#endif
515
}
516
517
518