9 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_0 0 10 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_1 1 11 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_2 2 12 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 3 13 #define AP_PARACHUTE_TRIGGER_TYPE_SERVO 10 15 #define AP_PARACHUTE_RELEASE_DELAY_MS 500 // delay in milliseconds between call to release() and when servo or relay actually moves. Allows for warning to user 16 #define AP_PARACHUTE_RELEASE_DURATION_MS 2000 // when parachute is released, servo or relay stay at their released position/value for 2000ms (2seconds) 18 #define AP_PARACHUTE_SERVO_ON_PWM_DEFAULT 1300 // default PWM value to move servo to when shutter is activated 19 #define AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT 1100 // default PWM value to move servo to when shutter is deactivated 21 #define AP_PARACHUTE_ALT_MIN_DEFAULT 10 // default min altitude the vehicle should have before parachute is released
void update()
update - shuts off the trigger should be called at about 10hz
bool release_in_progress() const
release_in_progress - true if the parachute release sequence is in progress
static const struct AP_Param::GroupInfo var_info[]
bool _release_in_progress
bool released() const
released - true if the parachute has been released (or release is in progress)
A system for managing and storing variables that are of general interest to the system.
bool release_initiated() const
release_initiated - true if the parachute release sequence has been initiated (may wait before actual...
Class managing the release of a parachute.
bool enabled() const
enabled - returns true if parachute release is enabled
Common definitions and utility routines for the ArduPilot libraries.
Class to manage the ArduPilot relay.
void release()
release - release parachute
AP_Parachute & operator=(const AP_Parachute &)=delete
AP_Parachute(AP_Relay &relay)
Constructor.
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)