Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Disarm after parachute release #25570

Closed
wants to merge 7 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions ArduPlane/commands_logic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,13 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_NAV_DELAY:
mode_auto.do_nav_delay(cmd);
break;

case MAV_CMD_DO_PARACHUTE:
if (cmd.p1 == PARACHUTE_RELEASE) {
// stop motors to avoid parachute tangling
plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false);
}
break;

default:
// unable to use the command, allow the vehicle to try the next command
Expand Down
4 changes: 0 additions & 4 deletions ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,8 +140,6 @@ 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 avoid 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);
Expand Down Expand Up @@ -183,8 +181,6 @@ 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 avoid 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);
Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,9 @@ void Plane::parachute_release()
// release parachute
parachute.release();

// stop motors to avoid parachute tangling
plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false);

#if AP_LANDINGGEAR_ENABLED
// deploy landing gear
g2.landing_gear.set_position(AP_LandingGear::LandingGear_Deploy);
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -434,6 +434,9 @@ bool AP_Mission::start_command(const Mission_Command& cmd)
return start_command_camera(cmd);
#endif
case MAV_CMD_DO_PARACHUTE:
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
_cmd_start_fn(cmd);
#endif
return start_command_parachute(cmd);
case MAV_CMD_DO_SEND_SCRIPT_MESSAGE:
return start_command_do_scripting(cmd);
Expand Down