AP_Parachute: added CHUTE_OPTIONS

allow for servo release forever to cope with high altitude drops where
servo may be frozen
This commit is contained in:
Andrew Tridgell 2021-01-22 12:38:59 +11:00
parent f91e995e98
commit 95cbb69d3c
2 changed files with 18 additions and 3 deletions

View File

@ -74,6 +74,12 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = {
// @User: Standard
AP_GROUPINFO("CRT_SINK", 6, AP_Parachute, _critical_sink, AP_PARACHUTE_CRITICAL_SINK_DEFAULT),
// @Param: OPTIONS
// @DisplayName: Parachute options
// @Description: Optional behaviour for parachute
// @Bitmask: 0:hold open forever after release
// @User: Standard
AP_GROUPINFO("OPTIONS", 7, AP_Parachute, _options, 0),
AP_GROUPEND
};
@ -123,6 +129,8 @@ void AP_Parachute::update()
uint32_t time_diff = AP_HAL::millis() - _release_time;
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
bool hold_forever = (_options.get() & uint32_t(Options::HoldOpen)) != 0;
// check if we should release parachute
if ((_release_time != 0) && !_release_in_progress) {
if (time_diff >= delay_ms) {
@ -136,7 +144,8 @@ void AP_Parachute::update()
_release_in_progress = true;
_released = true;
}
} else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
} else if ((_release_time == 0) ||
(!hold_forever && time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS)) {
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
// move servo back to off position
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);

View File

@ -113,6 +113,12 @@ private:
bool _released:1; // true if the parachute has been released
bool _is_flying:1; // true if the vehicle is flying
uint32_t _sink_time_ms; // system time that the vehicle exceeded critical sink rate
enum class Options : uint8_t {
HoldOpen = (1U<<0),
};
AP_Int32 _options;
};
namespace AP {