2015-08-11 03:28:45 -03:00
# include "AP_Parachute.h"
2020-01-17 18:57:09 -04:00
# if HAL_PARACHUTE_ENABLED
2015-08-11 03:28:45 -03:00
# 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>
2019-02-01 17:48:19 -04:00
# include <AP_Logger/AP_Logger.h>
# include <GCS_MAVLink/GCS.h>
2024-04-08 20:17:13 -03:00
# include <AP_Arming/AP_Arming.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)
2023-12-28 18:48:32 -04:00
// @Description: Parachute release mechanism type (relay number in versions prior to 4.5, or servo). Values 0-3 all are relay. Relay number used for release is set by RELAYx_FUNCTION in 4.5 or later.
// @Values: 0: 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
2017-05-15 20:22:18 -03:00
// @Description: Parachute Servo PWM value in microseconds when parachute is released
2014-04-01 08:57:03 -03:00
// @Range: 1000 2000
2017-05-02 10:46:58 -03:00
// @Units: PWM
2014-04-01 08:57:03 -03:00
// @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
2017-05-15 20:22:18 -03:00
// @Description: Parachute Servo PWM value in microseconds when parachute is not released
2014-04-01 08:57:03 -03:00
// @Range: 1000 2000
2017-05-02 10:46:58 -03:00
// @Units: PWM
2014-04-01 08:57:03 -03:00
// @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
2017-05-02 10:46:58 -03:00
// @Units: m
2014-04-06 23:17:07 -03:00
// @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
2017-05-02 10:46:58 -03:00
// @Units: ms
2016-03-28 15:48:40 -03:00
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " DELAY_MS " , 5 , AP_Parachute , _delay_ms , AP_PARACHUTE_RELEASE_DELAY_MS ) ,
2024-04-08 20:17:13 -03:00
2019-02-21 09:04:33 -04:00
// @Param: CRT_SINK
// @DisplayName: Critical sink speed rate in m/s to trigger emergency parachute
// @Description: Release parachute when critical sink rate is reached
// @Range: 0 15
// @Units: m/s
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " CRT_SINK " , 6 , AP_Parachute , _critical_sink , AP_PARACHUTE_CRITICAL_SINK_DEFAULT ) ,
2021-01-21 21:38:59 -04:00
// @Param: OPTIONS
// @DisplayName: Parachute options
// @Description: Optional behaviour for parachute
2024-04-08 20:17:13 -03:00
// @Bitmask: 0:hold open forever after release,1:skip disarm before parachute release
2021-01-21 21:38:59 -04:00
// @User: Standard
2024-04-08 20:17:13 -03:00
AP_GROUPINFO ( " OPTIONS " , 7 , AP_Parachute , _options , AP_PARACHUTE_OPTIONS_DEFAULT ) ,
2021-01-21 21:38:59 -04:00
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 )
{
2022-07-05 00:08:56 -03:00
_enabled . set ( on_off ) ;
2014-04-03 11:05:41 -03:00
2014-04-24 07:20:04 -03:00
// clear release_time
_release_time = 0 ;
2019-02-01 17:48:19 -04:00
2023-07-13 21:58:07 -03:00
LOGGER_WRITE_EVENT ( _enabled ? LogEvent : : PARACHUTE_ENABLED : LogEvent : : PARACHUTE_DISABLED ) ;
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 ;
}
2023-09-02 02:21:35 -03:00
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " Parachute: Released " ) ;
2023-07-13 21:58:07 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : PARACHUTE_RELEASED ) ;
2019-02-01 17:48:19 -04:00
2024-04-08 20:17:13 -03:00
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 ) ;
}
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
2023-09-24 06:01:06 -03:00
AP_Notify : : flags . parachute_release = true ;
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 ;
}
2020-09-16 03:24:40 -03:00
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 ;
2020-09-16 02:40:26 -03:00
2021-01-21 21:38:59 -04:00
bool hold_forever = ( _options . get ( ) & uint32_t ( Options : : HoldOpen ) ) ! = 0 ;
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 ) ;
2023-06-06 05:05:06 -03:00
# if AP_RELAY_ENABLED
2020-09-16 02:40:26 -03:00
} else if ( _release_type < = AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 ) {
2014-04-03 11:05:41 -03:00
// set relay
2022-12-22 19:55:03 -04:00
AP_Relay * _relay = AP : : relay ( ) ;
if ( _relay ! = nullptr ) {
2023-12-08 00:36:47 -04:00
_relay - > set ( AP_Relay_Params : : FUNCTION : : PARACHUTE , true ) ;
2022-12-22 19:55:03 -04:00
}
2023-06-06 05:05:06 -03:00
# endif
2014-04-03 11:05:41 -03:00
}
2015-10-26 20:36:04 -03:00
_release_in_progress = true ;
2014-04-03 11:05:41 -03:00
_released = true ;
}
2021-01-21 21:38:59 -04:00
} else if ( ( _release_time = = 0 ) | |
( ! hold_forever & & 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 ) ;
2023-06-06 05:05:06 -03:00
# if AP_RELAY_ENABLED
2020-09-16 02:40:26 -03:00
} else if ( _release_type < = AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 ) {
2014-04-01 08:57:03 -03:00
// set relay back to zero volts
2022-12-22 19:55:03 -04:00
AP_Relay * _relay = AP : : relay ( ) ;
if ( _relay ! = nullptr ) {
2023-12-08 00:36:47 -04:00
_relay - > set ( AP_Relay_Params : : FUNCTION : : PARACHUTE , false ) ;
2022-12-22 19:55:03 -04:00
}
2023-06-06 05:05:06 -03:00
# endif
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
2023-09-24 06:01:06 -03:00
AP_Notify : : flags . parachute_release = false ;
2014-04-01 08:57:03 -03:00
}
}
2019-02-01 17:48:19 -04:00
2020-09-16 03:24:40 -03:00
// set_sink_rate - set vehicle sink rate
void AP_Parachute : : set_sink_rate ( float sink_rate )
{
// reset sink time if critical sink rate check is disabled or vehicle is not flying
if ( ( _critical_sink < = 0 ) | | ! _is_flying ) {
_sink_time_ms = 0 ;
return ;
}
// reset sink_time if vehicle is not sinking too fast
if ( sink_rate < = _critical_sink ) {
_sink_time_ms = 0 ;
return ;
}
// start time when sinking too fast
if ( _sink_time_ms = = 0 ) {
_sink_time_ms = AP_HAL : : millis ( ) ;
}
}
// trigger parachute release if sink_rate is below critical_sink_rate for 1sec
void AP_Parachute : : check_sink_rate ( )
{
// return immediately if parachute is being released or vehicle is not flying
if ( _release_initiated | | ! _is_flying ) {
return ;
}
// if vehicle is sinking too fast for more than a second release parachute
if ( ( _sink_time_ms > 0 ) & & ( ( AP_HAL : : millis ( ) - _sink_time_ms ) > 1000 ) ) {
release ( ) ;
}
}
2021-07-20 01:36:10 -03:00
// check settings are valid
bool AP_Parachute : : arming_checks ( size_t buflen , char * buffer ) const
{
if ( _enabled > 0 ) {
if ( _release_type = = AP_PARACHUTE_TRIGGER_TYPE_SERVO ) {
if ( ! SRV_Channels : : function_assigned ( SRV_Channel : : k_parachute_release ) ) {
hal . util - > snprintf ( buffer , buflen , " Chute has no channel " ) ;
return false ;
}
2022-12-22 19:55:03 -04:00
} else {
2023-06-06 05:05:06 -03:00
# if AP_RELAY_ENABLED
2022-12-22 19:55:03 -04:00
AP_Relay * _relay = AP : : relay ( ) ;
2023-12-08 00:36:47 -04:00
if ( _relay = = nullptr | | ! _relay - > enabled ( AP_Relay_Params : : FUNCTION : : PARACHUTE ) ) {
hal . util - > snprintf ( buffer , buflen , " Chute has no relay " ) ;
2022-12-22 19:55:03 -04:00
return false ;
}
2023-06-06 05:05:06 -03:00
# else
hal . util - > snprintf ( buffer , buflen , " AP_Relay not available " ) ;
# endif
2021-07-20 01:36:10 -03:00
}
2023-06-06 05:05:06 -03:00
2021-11-17 04:53:33 -04:00
if ( _release_initiated ) {
hal . util - > snprintf ( buffer , buflen , " Chute is released " ) ;
return false ;
}
2021-07-20 01:36:10 -03:00
}
return true ;
}
2023-12-08 00:36:47 -04:00
# if AP_RELAY_ENABLED
// Return the relay index that would be used for param conversion to relay functions
bool AP_Parachute : : get_legacy_relay_index ( int8_t & index ) const
{
// PARAMETER_CONVERSION - Added: Dec-2023
2024-02-06 10:59:08 -04:00
if ( _release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 ) {
// Not relay type
return false ;
}
if ( ! enabled ( ) & & ! _enabled . configured ( ) ) {
// Disabled and parameter never changed
// Copter manual parachute release enables and deploys in one step
// This means it is possible for parachute to still function correctly if disabled at boot
// Checking if the enable param is configured means the user must have setup chute at some point
// this means relay parm conversion will be done if parachute has ever been enabled
// Parachute has priority in relay param conversion, so this might mean we overwrite some other function
2023-12-08 00:36:47 -04:00
return false ;
}
index = _release_type ;
return true ;
}
# endif
2019-02-01 17:48:19 -04:00
// singleton instance
AP_Parachute * AP_Parachute : : _singleton ;
namespace AP {
AP_Parachute * parachute ( )
{
return AP_Parachute : : get_singleton ( ) ;
}
}
2020-01-17 18:57:09 -04:00
# endif // HAL_PARACHUTE_ENABLED