Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_Parachute / AP_Parachute.h
blob8c88c2be26a3bb65eabe5edb7b9eeee6ef79a169
1 /// @file AP_Parachute.h
2 /// @brief Parachute release library
3 #pragma once
5 #include "AP_Parachute_config.h"
7 #if HAL_PARACHUTE_ENABLED
9 #include <AP_Param/AP_Param.h>
10 #include <AP_Common/AP_Common.h>
12 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_0 0
13 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_1 1
14 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_2 2
15 #define AP_PARACHUTE_TRIGGER_TYPE_RELAY_3 3
16 #define AP_PARACHUTE_TRIGGER_TYPE_SERVO 10
18 #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
19 #define AP_PARACHUTE_RELEASE_DURATION_MS 2000 // when parachute is released, servo or relay stay at their released position/value for 2000ms (2seconds)
21 #define AP_PARACHUTE_SERVO_ON_PWM_DEFAULT 1300 // default PWM value to move servo to when shutter is activated
22 #define AP_PARACHUTE_SERVO_OFF_PWM_DEFAULT 1100 // default PWM value to move servo to when shutter is deactivated
24 #define AP_PARACHUTE_ALT_MIN_DEFAULT 10 // default min altitude the vehicle should have before parachute is released
26 #define AP_PARACHUTE_CRITICAL_SINK_DEFAULT 0 // default critical sink speed in m/s to trigger emergency parachute
27 #define AP_PARACHUTE_OPTIONS_DEFAULT 0 // default parachute options: enabled disarm after parachute release
29 /// @class AP_Parachute
30 /// @brief Class managing the release of a parachute
31 class AP_Parachute {
33 public:
34 /// Constructor
35 AP_Parachute()
37 // setup parameter defaults
38 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
39 if (_singleton != nullptr) {
40 AP_HAL::panic("Parachute must be singleton");
42 #endif
43 _singleton = this;
44 AP_Param::setup_object_defaults(this, var_info);
47 /* Do not allow copies */
48 CLASS_NO_COPY(AP_Parachute);
50 /// enabled - enable or disable parachute release
51 void enabled(bool on_off);
53 /// enabled - returns true if parachute release is enabled
54 bool enabled() const { return _enabled; }
56 /// release - release parachute
57 void release();
59 /// released - true if the parachute has been released (or release is in progress)
60 bool released() const { return _released; }
62 /// release_initiated - true if the parachute release sequence has been initiated (may wait before actual release)
63 bool release_initiated() const { return _release_initiated; }
65 /// release_in_progress - true if the parachute release sequence is in progress
66 bool release_in_progress() const { return _release_in_progress; }
68 /// update - shuts off the trigger should be called at about 10hz
69 void update();
71 /// alt_min - returns the min altitude above home the vehicle should have before parachute is released
72 /// 0 = altitude check disabled
73 int16_t alt_min() const { return _alt_min; }
75 /// set_is_flying - accessor to the is_flying flag
76 void set_is_flying(const bool is_flying) { _is_flying = is_flying; }
78 // set_sink_rate - set vehicle sink rate
79 void set_sink_rate(float sink_rate);
81 // trigger parachute release if sink_rate is below critical_sink_rate for 1sec
82 void check_sink_rate();
84 // check settings are valid
85 bool arming_checks(size_t buflen, char *buffer) const;
87 // Return the relay index that would be used for param conversion to relay functions
88 bool get_legacy_relay_index(int8_t &index) const;
90 static const struct AP_Param::GroupInfo var_info[];
92 // get singleton instance
93 static AP_Parachute *get_singleton() { return _singleton; }
95 private:
96 static AP_Parachute *_singleton;
97 // Parameters
98 AP_Int8 _enabled; // 1 if parachute release is enabled
99 AP_Int8 _release_type; // 0:Servo,1:Relay
100 AP_Int16 _servo_on_pwm; // PWM value to move servo to when shutter is activated
101 AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
102 AP_Int16 _alt_min; // min altitude the vehicle should have before parachute is released
103 AP_Int16 _delay_ms; // delay before chute release for motors to stop
104 AP_Float _critical_sink; // critical sink rate to trigger emergency parachute
106 // internal variables
107 uint32_t _release_time; // system time that parachute is ordered to be released (actual release will happen 0.5 seconds later)
108 bool _release_initiated:1; // true if the parachute release initiated (may still be waiting for engine to be suppressed etc.)
109 bool _release_in_progress:1; // true if the parachute release is in progress
110 bool _released:1; // true if the parachute has been released
111 bool _is_flying:1; // true if the vehicle is flying
112 uint32_t _sink_time_ms; // system time that the vehicle exceeded critical sink rate
114 enum class Options : uint8_t {
115 HoldOpen = (1U<<0),
116 SkipDisarmBeforeParachuteRelease = (1U<<1),
119 AP_Int32 _options;
122 namespace AP {
123 AP_Parachute *parachute();
126 #endif // HAL_PARACHUTE_ENABLED