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/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
AP_AdvancedFailsafe.cpp
18
19
This is an advanced failsafe module originally modelled on the
20
failsafe rules of the Outback Challenge
21
*/
22
#include "AP_AdvancedFailsafe.h"
23
24
#if AP_ADVANCEDFAILSAFE_ENABLED
25
26
#include <AP_HAL/AP_HAL.h>
27
#include <RC_Channel/RC_Channel.h>
28
#include <SRV_Channel/SRV_Channel.h>
29
#include <GCS_MAVLink/GCS.h>
30
#include <AP_GPS/AP_GPS.h>
31
#include <AP_Baro/AP_Baro.h>
32
#include <AP_Mission/AP_Mission.h>
33
#include <AC_Fence/AC_Fence.h>
34
35
AP_AdvancedFailsafe *AP_AdvancedFailsafe::_singleton;
36
37
extern const AP_HAL::HAL& hal;
38
39
// table of user settable parameters
40
const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
41
// @Param: ENABLE
42
// @DisplayName: Enable Advanced Failsafe
43
// @Description: This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
44
// @User: Advanced
45
AP_GROUPINFO_FLAGS("ENABLE", 11, AP_AdvancedFailsafe, _enable, 0, AP_PARAM_FLAG_ENABLE),
46
47
// @Param: MAN_PIN
48
// @DisplayName: Manual Pin
49
// @Description: This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
50
// @User: Advanced
51
AP_GROUPINFO("MAN_PIN", 0, AP_AdvancedFailsafe, _manual_pin, -1),
52
53
// @Param: HB_PIN
54
// @DisplayName: Heartbeat Pin
55
// @Description: This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
56
// @User: Advanced
57
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
58
AP_GROUPINFO("HB_PIN", 1, AP_AdvancedFailsafe, _heartbeat_pin, -1),
59
60
// @Param: WP_COMMS
61
// @DisplayName: Comms Waypoint
62
// @Description: Waypoint number to navigate to on comms loss
63
// @User: Advanced
64
AP_GROUPINFO("WP_COMMS", 2, AP_AdvancedFailsafe, _wp_comms_hold, 0),
65
66
// @Param: WP_GPS_LOSS
67
// @DisplayName: GPS Loss Waypoint
68
// @Description: Waypoint number to navigate to on GPS lock loss
69
// @User: Advanced
70
AP_GROUPINFO("WP_GPS_LOSS", 4, AP_AdvancedFailsafe, _wp_gps_loss, 0),
71
72
// @Param: TERMINATE
73
// @DisplayName: Force Terminate
74
// @Description: Can be set in flight to force termination of the heartbeat signal
75
// @User: Advanced
76
AP_GROUPINFO("TERMINATE", 5, AP_AdvancedFailsafe, _terminate, 0),
77
78
// @Param: TERM_ACTION
79
// @DisplayName: Terminate action
80
// @Description: This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter
81
// @User: Advanced
82
AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
83
84
// @Param: TERM_PIN
85
// @DisplayName: Terminate Pin
86
// @Description: This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.
87
// @User: Advanced
88
// @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5
89
AP_GROUPINFO("TERM_PIN", 7, AP_AdvancedFailsafe, _terminate_pin, -1),
90
91
// @Param: AMSL_LIMIT
92
// @DisplayName: AMSL limit
93
// @Description: This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
94
// @User: Advanced
95
// @Units: m
96
AP_GROUPINFO("AMSL_LIMIT", 8, AP_AdvancedFailsafe, _amsl_limit, 0),
97
98
// @Param: AMSL_ERR_GPS
99
// @DisplayName: Error margin for GPS based AMSL limit
100
// @Description: This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
101
// @User: Advanced
102
// @Units: m
103
AP_GROUPINFO("AMSL_ERR_GPS", 9, AP_AdvancedFailsafe, _amsl_margin_gps, -1),
104
105
// @Param: QNH_PRESSURE
106
// @DisplayName: QNH pressure
107
// @Description: This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
108
// @Units: hPa
109
// @User: Advanced
110
AP_GROUPINFO("QNH_PRESSURE", 10, AP_AdvancedFailsafe, _qnh_pressure, 0),
111
112
// *NOTE* index 11 is "Enable" and is moved to the top to allow AP_PARAM_FLAG_ENABLE
113
114
// *NOTE* index 12 of AP_Int16 RC_FAIL_MS was depreciated. Replaced by RC_FAIL_TIME.
115
116
// @Param: MAX_GPS_LOSS
117
// @DisplayName: Maximum number of GPS loss events
118
// @Description: Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
119
// @User: Advanced
120
AP_GROUPINFO("MAX_GPS_LOSS", 13, AP_AdvancedFailsafe, _max_gps_loss, 0),
121
122
// @Param: MAX_COM_LOSS
123
// @DisplayName: Maximum number of comms loss events
124
// @Description: Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
125
// @User: Advanced
126
AP_GROUPINFO("MAX_COM_LOSS", 14, AP_AdvancedFailsafe, _max_comms_loss, 0),
127
128
// @Param: GEOFENCE
129
// @DisplayName: Enable geofence Advanced Failsafe
130
// @Description: This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
131
// @User: Advanced
132
AP_GROUPINFO("GEOFENCE", 15, AP_AdvancedFailsafe, _enable_geofence_fs, 1),
133
134
// @Param: RC
135
// @DisplayName: Enable RC Advanced Failsafe
136
// @Description: This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
137
// @User: Advanced
138
AP_GROUPINFO("RC", 16, AP_AdvancedFailsafe, _enable_RC_fs, 1),
139
140
// @Param: RC_MAN_ONLY
141
// @DisplayName: Enable RC Termination only in manual control modes
142
// @Description: If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
143
// @User: Advanced
144
AP_GROUPINFO("RC_MAN_ONLY", 17, AP_AdvancedFailsafe, _rc_term_manual_only, 1),
145
146
// @Param: DUAL_LOSS
147
// @DisplayName: Enable dual loss terminate due to failure of both GCS and GPS simultaneously
148
// @Description: This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
149
// @User: Advanced
150
AP_GROUPINFO("DUAL_LOSS", 18, AP_AdvancedFailsafe, _enable_dual_loss, 1),
151
152
// @Param: RC_FAIL_TIME
153
// @DisplayName: RC failure time
154
// @Description: This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
155
// @User: Advanced
156
// @Units: s
157
AP_GROUPINFO("RC_FAIL_TIME", 19, AP_AdvancedFailsafe, _rc_fail_time_seconds, 0),
158
159
// @Param: MAX_RANGE
160
// @DisplayName: Max allowed range
161
// @Description: This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
162
// @User: Advanced
163
// @Units: km
164
AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),
165
166
// @Param: OPTIONS
167
// @DisplayName: AFS options
168
// @Description: See description for each bitmask bit description
169
// @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)
170
// @Bitmask: 1: Enable AFS for all autonomous modes (not just AUTO)
171
AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0),
172
173
// @Param: GCS_TIMEOUT
174
// @DisplayName: GCS timeout
175
// @Description: The time (in seconds) of persistent data link loss before GCS failsafe occurs.
176
// @User: Advanced
177
// @Units: s
178
AP_GROUPINFO("GCS_TIMEOUT", 22, AP_AdvancedFailsafe, _gcs_fail_time_seconds, 10),
179
180
AP_GROUPEND
181
};
182
183
// check for Failsafe conditions. This is called at 10Hz by the main
184
// ArduPlane code
185
void
186
AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)
187
{
188
if (!_enable) {
189
return;
190
}
191
192
#if AP_FENCE_ENABLED
193
// we always check for fence breach
194
if(_enable_geofence_fs) {
195
const AC_Fence *ap_fence = AP::fence();
196
if ((ap_fence != nullptr && ap_fence->get_breaches() != 0) || check_altlimit()) {
197
if (!_terminate) {
198
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to fence breach");
199
_terminate.set_and_notify(1);
200
}
201
}
202
}
203
#endif
204
205
// update max range check
206
max_range_update();
207
208
enum control_mode mode = afs_mode();
209
210
// check if RC termination is enabled
211
// check for RC failure in manual mode or RC failure when AFS_RC_MANUAL is 0
212
if (_state != STATE_PREFLIGHT && !_terminate && _enable_RC_fs &&
213
(mode == AFS_MANUAL || mode == AFS_STABILIZED || !_rc_term_manual_only) &&
214
_rc_fail_time_seconds > 0 &&
215
(AP_HAL::millis() - last_valid_rc_ms) > (_rc_fail_time_seconds * 1000.0f)) {
216
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to RC failure");
217
_terminate.set_and_notify(1);
218
}
219
220
// tell the failsafe board if we are in manual control
221
// mode. This tells it to pass through controls from the
222
// receiver
223
if (_manual_pin != -1) {
224
hal.gpio->pinMode(_manual_pin, HAL_GPIO_OUTPUT);
225
hal.gpio->write(_manual_pin, mode==AFS_MANUAL);
226
}
227
228
const uint32_t last_heartbeat_ms = gcs().sysid_myggcs_last_seen_time_ms();
229
uint32_t now = AP_HAL::millis();
230
bool gcs_link_ok = ((now - last_heartbeat_ms) < (_gcs_fail_time_seconds*1000.0f));
231
bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000);
232
233
AP_Mission *_mission = AP::mission();
234
if (_mission == nullptr) {
235
return;
236
}
237
AP_Mission &mission = *_mission;
238
239
switch (_state) {
240
case STATE_PREFLIGHT:
241
// we startup in preflight mode. This mode ends when
242
// we first enter auto.
243
if (mode == AFS_AUTO) {
244
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO");
245
_state = STATE_AUTO;
246
}
247
break;
248
249
case STATE_AUTO:
250
// this is the normal mode.
251
if (!gcs_link_ok) {
252
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: DATA_LINK_LOSS");
253
_state = STATE_DATA_LINK_LOSS;
254
if (_wp_comms_hold) {
255
_saved_wp = mission.get_current_nav_cmd().index;
256
mission.set_current_cmd(_wp_comms_hold);
257
if (mode == AFS_AUTO && option_is_set(Option::GCS_FS_ALL_AUTONOMOUS_MODES)) {
258
set_mode_auto();
259
}
260
}
261
// if two events happen within 30s we consider it to be part of the same event
262
if (now - _last_comms_loss_ms > 30*1000UL) {
263
_comms_loss_count++;
264
_last_comms_loss_ms = now;
265
}
266
break;
267
}
268
if (!gps_lock_ok) {
269
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: GPS_LOSS");
270
_state = STATE_GPS_LOSS;
271
if (_wp_gps_loss) {
272
_saved_wp = mission.get_current_nav_cmd().index;
273
mission.set_current_cmd(_wp_gps_loss);
274
}
275
// if two events happen within 30s we consider it to be part of the same event
276
if (now - _last_gps_loss_ms > 30*1000UL) {
277
_gps_loss_count++;
278
_last_gps_loss_ms = now;
279
}
280
break;
281
}
282
break;
283
284
case STATE_DATA_LINK_LOSS:
285
if (!gps_lock_ok) {
286
// losing GPS lock when data link is lost
287
// leads to termination if AFS_DUAL_LOSS is 1
288
if(_enable_dual_loss) {
289
if (!_terminate) {
290
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
291
_terminate.set_and_notify(1);
292
}
293
}
294
} else if (gcs_link_ok) {
295
_state = STATE_AUTO;
296
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");
297
298
if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) {
299
break;
300
}
301
302
// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
303
if (_saved_wp != 0 &&
304
(_max_comms_loss <= 0 ||
305
_comms_loss_count <= _max_comms_loss)) {
306
mission.set_current_cmd(_saved_wp);
307
_saved_wp = 0;
308
}
309
}
310
break;
311
312
case STATE_GPS_LOSS:
313
if (!gcs_link_ok) {
314
// losing GCS link when GPS lock lost
315
// leads to termination if AFS_DUAL_LOSS is 1
316
if (!_terminate && _enable_dual_loss) {
317
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to dual loss");
318
_terminate.set_and_notify(1);
319
}
320
} else if (gps_lock_ok) {
321
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GPS now OK");
322
_state = STATE_AUTO;
323
// we only return to the mission if we have not exceeded AFS_MAX_GPS_LOSS
324
if (_saved_wp != 0 &&
325
(_max_gps_loss <= 0 || _gps_loss_count <= _max_gps_loss)) {
326
mission.set_current_cmd(_saved_wp);
327
_saved_wp = 0;
328
}
329
}
330
break;
331
}
332
333
// if we are not terminating or if there is a separate terminate
334
// pin configured then toggle the heartbeat pin at 10Hz
335
heartbeat();
336
337
// set the terminate pin
338
if (_terminate_pin != -1) {
339
hal.gpio->pinMode(_terminate_pin, HAL_GPIO_OUTPUT);
340
hal.gpio->write(_terminate_pin, _terminate?1:0);
341
}
342
}
343
344
345
// send heartbeat messages during sensor calibration
346
void
347
AP_AdvancedFailsafe::heartbeat(void)
348
{
349
if (!_enable) {
350
return;
351
}
352
353
// if we are not terminating or if there is a separate terminate
354
// pin configured then toggle the heartbeat pin at 10Hz
355
if (_heartbeat_pin != -1 && (_terminate_pin != -1 || !_terminate)) {
356
_heartbeat_pin_value = !_heartbeat_pin_value;
357
hal.gpio->pinMode(_heartbeat_pin, HAL_GPIO_OUTPUT);
358
hal.gpio->write(_heartbeat_pin, _heartbeat_pin_value);
359
}
360
}
361
362
// check for altitude limit breach
363
bool
364
AP_AdvancedFailsafe::check_altlimit(void)
365
{
366
if (!_enable) {
367
return false;
368
}
369
if (_amsl_limit == 0 || _qnh_pressure <= 0) {
370
// no limit set
371
return false;
372
}
373
374
// see if the barometer is dead
375
const AP_Baro &baro = AP::baro();
376
const AP_GPS &gps = AP::gps();
377
if (AP_HAL::millis() - baro.get_last_update() > 5000) {
378
// the barometer has been unresponsive for 5 seconds. See if we can switch to GPS
379
if (_amsl_margin_gps != -1 &&
380
gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
381
gps.location().alt*0.01f <= _amsl_limit - _amsl_margin_gps) {
382
// GPS based altitude OK
383
return false;
384
}
385
// no barometer - immediate termination
386
return true;
387
}
388
389
float alt_amsl = baro.get_altitude_difference(_qnh_pressure*100, baro.get_pressure());
390
if (alt_amsl > _amsl_limit) {
391
// pressure altitude breach
392
return true;
393
}
394
395
// all OK
396
return false;
397
}
398
399
/*
400
return true if we should crash the vehicle
401
*/
402
bool AP_AdvancedFailsafe::should_crash_vehicle(void)
403
{
404
if (!_enable) {
405
return false;
406
}
407
// ensure failsafe values are setup for if FMU crashes on PX4/Pixhawk
408
if (!_failsafe_setup) {
409
_failsafe_setup = true;
410
setup_IO_failsafe();
411
}
412
413
// determine if the vehicle should be crashed
414
// only possible if FS_TERM_ACTION is 42 and _terminate is non zero
415
// _terminate may be set via parameters, or a mavlink command
416
if (_terminate &&
417
(_terminate_action == TERMINATE_ACTION_TERMINATE ||
418
_terminate_action == TERMINATE_ACTION_LAND)) {
419
// we are terminating
420
return true;
421
}
422
423
// continue flying
424
return false;
425
}
426
427
// update GCS based termination
428
// returns true if AFS is in the desired termination state
429
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {
430
if (!_enable) {
431
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
432
return false;
433
}
434
435
_terminate.set_and_notify(should_terminate ? 1 : 0);
436
437
// evaluate if we will crash or not, as AFS must be enabled, and TERM_ACTION has to be correct
438
bool is_terminating = should_crash_vehicle();
439
440
if(should_terminate == is_terminating) {
441
if (is_terminating) {
442
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Terminating due to %s", reason);
443
} else {
444
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);
445
}
446
return true;
447
} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
448
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");
449
}
450
return false;
451
}
452
453
/*
454
update check of maximum range
455
*/
456
void AP_AdvancedFailsafe::max_range_update(void)
457
{
458
if (_max_range_km <= 0) {
459
return;
460
}
461
462
if (!_have_first_location) {
463
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
464
// wait for 3D fix
465
return;
466
}
467
if (!hal.util->get_soft_armed()) {
468
// wait for arming
469
return;
470
}
471
_first_location = AP::gps().location();
472
_have_first_location = true;
473
}
474
475
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
476
// don't trigger when dead-reckoning
477
return;
478
}
479
480
// check distance from first location
481
float distance_km = _first_location.get_distance(AP::gps().location()) * 0.001;
482
if (distance_km > _max_range_km) {
483
uint32_t now = AP_HAL::millis();
484
if (now - _term_range_notice_ms > 5000) {
485
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terminating due to range %.1fkm", distance_km);
486
_term_range_notice_ms = now;
487
}
488
_terminate.set_and_notify(1);
489
}
490
}
491
492
namespace AP {
493
494
AP_AdvancedFailsafe *advancedfailsafe()
495
{
496
return AP_AdvancedFailsafe::get_singleton();
497
}
498
499
};
500
501
#endif // AP_ADVANCEDFAILSAFE_ENABLED
502
503