2015-08-11 03:28:45 -03:00
|
|
|
#include "AP_Parachute.h"
|
|
|
|
#include <AP_Relay/AP_Relay.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2017-01-05 01:13:09 -04:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2015-08-11 03:28:45 -03:00
|
|
|
#include <AP_Notify/AP_Notify.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-04-01 08:57:03 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo AP_Parachute::var_info[] = {
|
2014-04-01 08:57:03 -03:00
|
|
|
|
|
|
|
// @Param: ENABLED
|
|
|
|
// @DisplayName: Parachute release enabled or disabled
|
|
|
|
// @Description: Parachute release enabled or disabled
|
|
|
|
// @Values: 0:Disabled,1:Enabled
|
|
|
|
// @User: Standard
|
2016-08-04 15:31:21 -03:00
|
|
|
AP_GROUPINFO_FLAGS("ENABLED", 0, AP_Parachute, _enabled, 0, AP_PARAM_FLAG_ENABLE),
|
2014-04-01 08:57:03 -03:00
|
|
|
|
|
|
|
// @Param: TYPE
|
|
|
|
// @DisplayName: Parachute release mechanism type (relay or servo)
|
|
|
|
// @Description: Parachute release mechanism type (relay or servo)
|
2014-04-06 23:22:48 -03:00
|
|
|
// @Values: 0:First Relay,1:Second Relay,2:Third Relay,3:Fourth Relay,10:Servo
|
2014-04-01 08:57:03 -03:00
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("TYPE", 1, AP_Parachute, _release_type, AP_PARACHUTE_TRIGGER_TYPE_RELAY_0),
|
|
|
|
|
|
|
|
// @Param: SERVO_ON
|
|
|
|
// @DisplayName: Parachute Servo ON PWM value
|
|
|
|
// @Description: Parachute Servo PWM value when parachute is released
|
|
|
|
// @Range: 1000 2000
|
|
|
|
// @Units: pwm
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("SERVO_ON", 2, AP_Parachute, _servo_on_pwm, AP_PARACHUTE_SERVO_ON_PWM_DEFAULT),
|
|
|
|
|
|
|
|
// @Param: SERVO_OFF
|
|
|
|
// @DisplayName: Servo OFF PWM value
|
|
|
|
// @Description: Parachute Servo PWM value when parachute is not released
|
|
|
|
// @Range: 1000 2000
|
|
|
|
// @Units: pwm
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("SERVO_OFF", 3, AP_Parachute, _servo_off_pwm, AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT),
|
|
|
|
|
|
|
|
// @Param: ALT_MIN
|
2015-02-12 13:16:35 -04:00
|
|
|
// @DisplayName: Parachute min altitude in meters above home
|
2014-04-03 05:53:45 -03:00
|
|
|
// @Description: Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
|
2014-04-06 23:17:07 -03:00
|
|
|
// @Range: 0 32000
|
|
|
|
// @Units: Meters
|
|
|
|
// @Increment: 1
|
2014-04-01 08:57:03 -03:00
|
|
|
// @User: Standard
|
2014-04-06 23:17:07 -03:00
|
|
|
AP_GROUPINFO("ALT_MIN", 4, AP_Parachute, _alt_min, AP_PARACHUTE_ALT_MIN_DEFAULT),
|
2014-04-01 08:57:03 -03:00
|
|
|
|
2016-03-28 15:48:40 -03:00
|
|
|
// @Param: DELAY_MS
|
|
|
|
// @DisplayName: Parachute release delay
|
|
|
|
// @Description: Delay in millseconds between motor stop and chute release
|
|
|
|
// @Range: 0 5000
|
|
|
|
// @Units: Milliseconds
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("DELAY_MS", 5, AP_Parachute, _delay_ms, AP_PARACHUTE_RELEASE_DELAY_MS),
|
|
|
|
|
2014-04-01 08:57:03 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
2014-04-03 11:05:41 -03:00
|
|
|
/// enabled - enable or disable parachute release
|
|
|
|
void AP_Parachute::enabled(bool on_off)
|
|
|
|
{
|
|
|
|
_enabled = on_off;
|
|
|
|
|
2014-04-24 07:20:04 -03:00
|
|
|
// clear release_time
|
|
|
|
_release_time = 0;
|
2014-04-03 11:05:41 -03:00
|
|
|
}
|
2014-04-01 08:57:03 -03:00
|
|
|
|
|
|
|
/// release - release parachute
|
|
|
|
void AP_Parachute::release()
|
|
|
|
{
|
|
|
|
// exit immediately if not enabled
|
|
|
|
if (_enabled <= 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-04-03 11:05:41 -03:00
|
|
|
// set release time to current system time
|
2015-10-26 21:47:34 -03:00
|
|
|
if (_release_time == 0) {
|
2015-11-19 23:13:41 -04:00
|
|
|
_release_time = AP_HAL::millis();
|
2015-10-26 21:47:34 -03:00
|
|
|
}
|
2014-04-03 10:04:51 -03:00
|
|
|
|
2016-04-05 04:39:55 -03:00
|
|
|
_release_initiated = true;
|
|
|
|
|
2014-04-03 10:04:51 -03:00
|
|
|
// update AP_Notify
|
|
|
|
AP_Notify::flags.parachute_release = 1;
|
2014-04-01 08:57:03 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/// update - shuts off the trigger should be called at about 10hz
|
|
|
|
void AP_Parachute::update()
|
|
|
|
{
|
2014-04-03 11:05:41 -03:00
|
|
|
// exit immediately if not enabled or parachute not to be released
|
2014-10-18 05:12:50 -03:00
|
|
|
if (_enabled <= 0) {
|
2014-04-01 08:57:03 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-04-03 11:05:41 -03:00
|
|
|
// calc time since release
|
2015-11-19 23:13:41 -04:00
|
|
|
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
2016-03-28 15:48:40 -03:00
|
|
|
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
|
|
|
|
|
2014-04-03 11:05:41 -03:00
|
|
|
// check if we should release parachute
|
2015-10-26 20:36:04 -03:00
|
|
|
if ((_release_time != 0) && !_release_in_progress) {
|
2016-03-28 15:48:40 -03:00
|
|
|
if (time_diff >= delay_ms) {
|
2014-04-03 11:05:41 -03:00
|
|
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
|
|
|
// move servo
|
2017-01-05 01:13:09 -04:00
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
|
2014-04-03 11:05:41 -03:00
|
|
|
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
|
|
|
// set relay
|
|
|
|
_relay.on(_release_type);
|
|
|
|
}
|
2015-10-26 20:36:04 -03:00
|
|
|
_release_in_progress = true;
|
2014-04-03 11:05:41 -03:00
|
|
|
_released = true;
|
|
|
|
}
|
2016-03-28 15:48:40 -03:00
|
|
|
}else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
2014-04-01 08:57:03 -03:00
|
|
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
|
|
|
// move servo back to off position
|
2017-01-05 01:13:09 -04:00
|
|
|
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);
|
2014-04-01 08:57:03 -03:00
|
|
|
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
|
|
|
// set relay back to zero volts
|
2014-04-03 10:04:51 -03:00
|
|
|
_relay.off(_release_type);
|
2014-04-01 08:57:03 -03:00
|
|
|
}
|
2014-04-03 11:05:41 -03:00
|
|
|
// reset released flag and release_time
|
2015-10-26 20:36:04 -03:00
|
|
|
_release_in_progress = false;
|
2014-04-01 08:57:03 -03:00
|
|
|
_release_time = 0;
|
2014-04-03 10:04:51 -03:00
|
|
|
// update AP_Notify
|
|
|
|
AP_Notify::flags.parachute_release = 0;
|
2014-04-01 08:57:03 -03:00
|
|
|
}
|
|
|
|
}
|