From 3a3afe42be912f5f7afee9a8455346f9cd18206f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Jan 2016 17:59:53 +1100 Subject: [PATCH] Plane: don't force disarm on parachute release in auto-throttle modes throttle is suppressed. In pilot controlled modes pilot can lower throttle --- ArduPlane/events.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 59031d1658..643ddaecbb 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -78,7 +78,6 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype) if(g.long_fs_action == 3) { #if PARACHUTE == ENABLED parachute_release(); - disarm_motors(); #endif } else if (g.long_fs_action == 2) { set_mode(FLY_BY_WIRE_A); @@ -98,7 +97,6 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype) if(g.long_fs_action == 3) { #if PARACHUTE == ENABLED parachute_release(); - disarm_motors(); #endif } else if (g.long_fs_action == 2) { set_mode(FLY_BY_WIRE_A);