APM:Libraries
AP_Parachute.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Param/AP_Param.h>
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Relay/AP_Relay.h>
8 
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
14 
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)
17 
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
20 
21 #define AP_PARACHUTE_ALT_MIN_DEFAULT 10 // default min altitude the vehicle should have before parachute is released
22 
25 class AP_Parachute {
26 
27 public:
30  : _relay(relay)
31  , _release_time(0)
32  , _release_initiated(false)
33  , _release_in_progress(false)
34  , _released(false)
35  {
36  // setup parameter defaults
38  }
39 
40  /* Do not allow copies */
41  AP_Parachute(const AP_Parachute &other) = delete;
42  AP_Parachute &operator=(const AP_Parachute&) = delete;
43 
45  void enabled(bool on_off);
46 
48  bool enabled() const { return _enabled; }
49 
51  void release();
52 
54  bool released() const { return _released; }
55 
57  bool release_initiated() const { return _release_initiated; }
58 
60  bool release_in_progress() const { return _release_in_progress; }
61 
63  void update();
64 
67  int16_t alt_min() const { return _alt_min; }
68 
69  static const struct AP_Param::GroupInfo var_info[];
70 
71 private:
72  // Parameters
73  AP_Int8 _enabled; // 1 if parachute release is enabled
74  AP_Int8 _release_type; // 0:Servo,1:Relay
75  AP_Int16 _servo_on_pwm; // PWM value to move servo to when shutter is activated
76  AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
77  AP_Int16 _alt_min; // min altitude the vehicle should have before parachute is released
78  AP_Int16 _delay_ms; // delay before chute release for motors to stop
79 
80  // internal variables
81  AP_Relay &_relay; // pointer to relay object from the base class Relay.
82  uint32_t _release_time; // system time that parachute is ordered to be released (actual release will happen 0.5 seconds later)
83  bool _release_initiated:1; // true if the parachute release initiated (may still be waiting for engine to be suppressed etc.)
84  bool _release_in_progress:1; // true if the parachute release is in progress
85  bool _released:1; // true if the parachute has been released
86 };
bool _release_initiated
Definition: AP_Parachute.h:83
AP_Int16 _servo_off_pwm
Definition: AP_Parachute.h:76
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
Definition: AP_Parachute.h:60
static AP_Relay relay
AP_Int8 _release_type
Definition: AP_Parachute.h:74
AP_Relay & _relay
Definition: AP_Parachute.h:81
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Parachute.h:69
bool _release_in_progress
Definition: AP_Parachute.h:84
bool released() const
released - true if the parachute has been released (or release is in progress)
Definition: AP_Parachute.h:54
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...
Definition: AP_Parachute.h:57
AP_Int16 _servo_on_pwm
Definition: AP_Parachute.h:75
AP_Int16 _alt_min
Definition: AP_Parachute.h:77
Class managing the release of a parachute.
Definition: AP_Parachute.h:25
bool enabled() const
enabled - returns true if parachute release is enabled
Definition: AP_Parachute.h:48
Common definitions and utility routines for the ArduPilot libraries.
Class to manage the ArduPilot relay.
Definition: AP_Relay.h:18
void release()
release - release parachute
AP_Parachute & operator=(const AP_Parachute &)=delete
uint32_t _release_time
Definition: AP_Parachute.h:82
AP_Int8 _enabled
Definition: AP_Parachute.h:73
int16_t alt_min() const
Definition: AP_Parachute.h:67
AP_Parachute(AP_Relay &relay)
Constructor.
Definition: AP_Parachute.h:29
APM relay control class.
AP_Int16 _delay_ms
Definition: AP_Parachute.h:78
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214