mirror of https://github.com/ArduPilot/ardupilot
AP_AdvancedFailsafe: Allow GCS teriminate to supply a reason cause
This commit is contained in:
parent
12fd19ea26
commit
dab13f0e34
|
@ -378,7 +378,7 @@ bool AP_AdvancedFailsafe::should_crash_vehicle(void)
|
||||||
|
|
||||||
// update GCS based termination
|
// update GCS based termination
|
||||||
// returns true if AFS is in the desired termination state
|
// returns true if AFS is in the desired termination state
|
||||||
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) {
|
bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate, const char *reason) {
|
||||||
if (!_enable) {
|
if (!_enable) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
|
gcs().send_text(MAV_SEVERITY_INFO, "AFS not enabled, can't terminate the vehicle");
|
||||||
return false;
|
return false;
|
||||||
|
@ -391,9 +391,9 @@ bool AP_AdvancedFailsafe::gcs_terminate(bool should_terminate) {
|
||||||
|
|
||||||
if(should_terminate == is_terminating) {
|
if(should_terminate == is_terminating) {
|
||||||
if (is_terminating) {
|
if (is_terminating) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to GCS request");
|
gcs().send_text(MAV_SEVERITY_INFO, "Terminating due to %s", reason);
|
||||||
} else {
|
} else {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to GCS request");
|
gcs().send_text(MAV_SEVERITY_INFO, "Aborting termination due to %s", reason);
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
|
} else if (should_terminate && _terminate_action != TERMINATE_ACTION_TERMINATE) {
|
||||||
|
|
|
@ -77,7 +77,7 @@ public:
|
||||||
bool should_crash_vehicle(void);
|
bool should_crash_vehicle(void);
|
||||||
|
|
||||||
// enables or disables a GCS based termination, returns true if AFS is in the desired termination state
|
// enables or disables a GCS based termination, returns true if AFS is in the desired termination state
|
||||||
bool gcs_terminate(bool should_terminate);
|
bool gcs_terminate(bool should_terminate, const char *reason);
|
||||||
|
|
||||||
// called to set all outputs to termination state
|
// called to set all outputs to termination state
|
||||||
virtual void terminate_vehicle(void) = 0;
|
virtual void terminate_vehicle(void) = 0;
|
||||||
|
|
Loading…
Reference in New Issue