Browse Source

AP_AdvancedFailsafe: Allow landing to be a termination action

master
Michael du Breuil 8 years ago committed by Tom Pittenger
parent
commit
0bbbb3d08d
  1. 12
      libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
  2. 5
      libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h

12
libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

@ -25,8 +25,6 @@ @@ -25,8 +25,6 @@
#include <SRV_Channel/SRV_Channel.h>
#include <GCS_MAVLink/GCS.h>
#define TERMINATE 42
extern const AP_HAL::HAL& hal;
// table of user settable parameters
@ -69,7 +67,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = { @@ -69,7 +67,7 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
// @Param: TERM_ACTION
// @DisplayName: Terminate action
// @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 APM to handle it here. If set to 0 (which is the default) then no extra action is taken. If set to the magic value 42 then the plane will deliberately crash itself by setting maximum throws on all surfaces, and zero throttle
// @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 APM to handle it here. Please consult the wiki for more information on the possible values of the parameter
// @User: Advanced
AP_GROUPINFO("TERM_ACTION", 6, AP_AdvancedFailsafe, _terminate_action, 0),
@ -363,8 +361,10 @@ bool AP_AdvancedFailsafe::should_crash_vehicle(void) @@ -363,8 +361,10 @@ bool AP_AdvancedFailsafe::should_crash_vehicle(void)
// determine if the vehicle should be crashed
// only possible if FS_TERM_ACTION is 42 and _terminate is non zero
// _terminate may be set via parameters, or a mavlink command
if (_terminate_action == TERMINATE && _terminate) {
// we are crashing
if (_terminate &&
(_terminate_action == TERMINATE_ACTION_TERMINATE ||
_terminate_action == TERMINATE_ACTION_LAND)) {
// we are terminating
return true;
}
@ -392,7 +392,7 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) { @@ -392,7 +392,7 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) {
gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to GCS request");
}
return true;
} else if (should_terminate && _terminate_action != TERMINATE) {
} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
gcs().send_text(MAV_SEVERITY_INFO, "Unable to terminate, termination is not configured");
}
return false;

5
libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h

@ -45,6 +45,11 @@ public: @@ -45,6 +45,11 @@ public:
STATE_GPS_LOSS = 3
};
enum terminate_action {
TERMINATE_ACTION_TERMINATE = 42,
TERMINATE_ACTION_LAND = 43
};
// Constructor
AP_AdvancedFailsafe(AP_Mission &_mission, AP_Baro &_baro, const AP_GPS &_gps, const RCMapper &_rcmap) :
mission(_mission),

Loading…
Cancel
Save