mirror of https://github.com/ArduPilot/ardupilot
Plane:disarm on parachute release FS
This commit is contained in:
parent
e6ac368972
commit
d8e205dd39
|
@ -131,6 +131,8 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute_release();
|
||||
//stop motors to avoide parachute tangling
|
||||
plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false);
|
||||
#endif
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(mode_fbwa, reason);
|
||||
|
@ -168,9 +170,12 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||
|
||||
case Mode::Number::AVOID_ADSB:
|
||||
case Mode::Number::GUIDED:
|
||||
|
||||
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute_release();
|
||||
//stop motors to avoide parachute tangling
|
||||
plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false);
|
||||
#endif
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(mode_fbwa, reason);
|
||||
|
|
Loading…
Reference in New Issue