mirror of https://github.com/ArduPilot/ardupilot
AP_Parachute: optional (CHUTE_OPTIONS:1) disarm defore parachute release
This commit is contained in:
parent
0a1d9b06b5
commit
ed6ddf725d
|
@ -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;
|
||||
|
||||
|
@ -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
|
||||
};
|
||||
|
@ -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();
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
#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_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release
|
||||
|
||||
#ifndef HAL_PARACHUTE_ENABLED
|
||||
// default to parachute enabled to match previous configs
|
||||
|
@ -115,6 +116,7 @@ private:
|
|||
|
||||
enum class Options : uint8_t {
|
||||
HoldOpen = (1U<<0),
|
||||
SkipDisarmBeforeParachuteRelease = (1U<<1),
|
||||
};
|
||||
|
||||
AP_Int32 _options;
|
||||
|
|
Loading…
Reference in New Issue