mirror of https://github.com/ArduPilot/ardupilot
Plane: don't force disarm on parachute release
in auto-throttle modes throttle is suppressed. In pilot controlled modes pilot can lower throttle
This commit is contained in:
parent
c7e8a48a55
commit
3a3afe42be
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue