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

AP_Parachute: Optional (CHUTE_OPTIONS:1) disarm before parachute release #26129

Merged
Merged
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
4 changes: 0 additions & 4 deletions ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,7 +269,6 @@ void Copter::parachute_check()
}

if (parachute.release_initiated()) {
copter.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE);
return;
}

Expand Down Expand Up @@ -331,9 +330,6 @@ void Copter::parachute_check()
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
void Copter::parachute_release()
{
// disarm motors
arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE);

// release parachute
parachute.release();

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 @@ -191,8 +189,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
13 changes: 10 additions & 3 deletions libraries/AP_Parachute/AP_Parachute.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Arming/AP_Arming.h>

extern const AP_HAL::HAL& hal;

Expand Down Expand Up @@ -65,7 +66,7 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @Increment: 1
// @User: Standard
AP_GROUPINFO("DELAY_MS", 5, AP_Parachute, _delay_ms, AP_PARACHUTE_RELEASE_DELAY_MS),

// @Param: CRT_SINK
// @DisplayName: Critical sink speed rate in m/s to trigger emergency parachute
// @Description: Release parachute when critical sink rate is reached
Expand All @@ -78,9 +79,9 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @Param: OPTIONS
// @DisplayName: Parachute options
// @Description: Optional behaviour for parachute
// @Bitmask: 0:hold open forever after release
// @Bitmask: 0:hold open forever after release,1:skip disarm before parachute release
// @User: Standard
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, 0),
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, AP_PARACHUTE_OPTIONS_DEFAULT),

AP_GROUPEND
};
Expand All @@ -107,6 +108,12 @@ void AP_Parachute::release()
GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Parachute: Released");
LOGGER_WRITE_EVENT(LogEvent::PARACHUTE_RELEASED);

bool need_disarm = (_options.get() & uint32_t(Options::SkipDisarmBeforeParachuteRelease)) == 0;
if (need_disarm) {
// stop motors to avoid parachute tangling
AP::arming().disarm(AP_Arming::Method::PARACHUTE_RELEASE);
}

// set release time to current system time
if (_release_time == 0) {
_release_time = AP_HAL::millis();
Expand Down
4 changes: 3 additions & 1 deletion libraries/AP_Parachute/AP_Parachute.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@

#define AP_PARACHUTE_ALT_MIN_DEFAULT 10 // default min altitude the vehicle should have before parachute is released

#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
#define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
#define AP_PARACHUTE_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release

#ifndef HAL_PARACHUTE_ENABLED
// default to parachute enabled to match previous configs
Expand Down Expand Up @@ -115,6 +116,7 @@ class AP_Parachute {

enum class Options : uint8_t {
HoldOpen = (1U<<0),
SkipDisarmBeforeParachuteRelease = (1U<<1),
};

AP_Int32 _options;
Expand Down
Loading