From 3c3392aae5665aa52af8598ff49f78723cbf6b2e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Oct 2015 15:17:13 +1100 Subject: [PATCH] Plane: improve error messages on failed parachute release --- ArduPlane/GCS_Mavlink.cpp | 12 +++++++++++- ArduPlane/Plane.h | 2 +- ArduPlane/parachute.cpp | 13 ++++++++++--- 3 files changed, 22 insertions(+), 5 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index c9c5317b86..2a6ba9698c 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1486,7 +1486,17 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case PARACHUTE_RELEASE: // treat as a manual release which performs some additional check of altitude - plane.parachute_manual_release(); + if (plane.parachute.released()) { + plane.gcs_send_text_fmt(PSTR("Parachute already released")); + result = MAV_RESULT_FAILED; + } else if (!plane.parachute.enabled()) { + plane.gcs_send_text_fmt(PSTR("Parachute not enabled")); + result = MAV_RESULT_FAILED; + } else { + if (!plane.parachute_manual_release()) { + result = MAV_RESULT_FAILED; + } + } break; default: result = MAV_RESULT_FAILED; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8fbe5bc9fd..d3e7534074 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -979,7 +979,7 @@ private: void do_parachute(const AP_Mission::Mission_Command& cmd); void parachute_check(); void parachute_release(); - void parachute_manual_release(); + bool parachute_manual_release(); public: void mavlink_delay_cb(); diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 6cc9632b34..14593c723f 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -32,20 +32,27 @@ void Plane::parachute_release() after performing some checks for pilot error checks if the vehicle is landed */ -void Plane::parachute_manual_release() +bool Plane::parachute_manual_release() { // exit immediately if parachute is not enabled if (!parachute.enabled() || parachute.released()) { - return; + return false; } // do not release if vehicle is not flying if (!is_flying()) { // warn user of reason for failure gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Parachute: not flying")); - return; + return false; + } + + if (relative_altitude() < parachute.alt_min()) { + gcs_send_text_fmt(PSTR("Parachute: too low")); + return false; } // if we get this far release parachute parachute_release(); + + return true; }