-
Notifications
You must be signed in to change notification settings - Fork 15.3k
Expand file tree
/
Copy pathfailsafe.h
More file actions
215 lines (187 loc) · 7.47 KB
/
failsafe.h
File metadata and controls
215 lines (187 loc) · 7.47 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include "framework.h"
class Failsafe : public FailsafeBase
{
public:
Failsafe(ModuleParams *parent) : FailsafeBase(parent) {}
void updateArmingState(const hrt_abstime &time_us, bool armed, const failsafe_flags_s &status_flags);
protected:
void checkStateAndMode(const hrt_abstime &time_us, const State &state,
const failsafe_flags_s &status_flags) override;
Action checkModeFallback(const failsafe_flags_s &status_flags, uint8_t user_intended_mode) const override;
uint8_t modifyUserIntendedMode(Action previous_action, Action current_action,
uint8_t user_intended_mode) const override;
hrt_abstime _armed_time{0};
bool _was_armed{false};
bool _manual_control_lost_at_arming{false}; ///< true if manual control was lost at arming time
uint8_t _battery_warning_at_arming{0}; ///< low battery state at arming time
private:
enum class LinkLossExceptionBits : int32_t {
Mission = (1 << 0),
AutoModes = (1 << 1),
Offboard = (1 << 2),
ExternalMode = (1 << 3),
AltitudeCruise = (1 << 4)
};
// COM_LOW_BAT_ACT parameter values
enum class LowBatteryAction : int32_t {
Warning = 0, // Warning
Return = 1, // Return mode (deprecated)
Land = 2, // Land mode
ReturnOrLand = 3 // Return mode at critically low level, Land mode at current position if reaching dangerously low levels
};
enum class offboard_loss_failsafe_mode : int32_t {
Position_mode = 0,
Altitude_mode = 1,
Stabilized = 2,
Return_mode = 3,
Land_mode = 4,
Hold_mode = 5,
Terminate = 6,
Disarm = 7,
};
enum class actuator_failure_failsafe_mode : int32_t {
Warning_only = 0,
Hold_mode = 1,
Land_mode = 2,
Return_mode = 3,
Terminate = 4,
};
enum class imbalanced_propeller_failsafe_mode : int32_t {
Disabled = -1,
Warning = 0,
Return = 1,
Land = 2,
};
enum class geofence_violation_action : int32_t {
None = 0,
Warning = 1,
Hold_mode = 2,
Return_mode = 3,
Terminate = 4,
Land_mode = 5,
};
enum class gcs_connection_loss_failsafe_mode : int32_t {
Disabled = 0,
Hold_mode = 1,
Return_mode = 2,
Land_mode = 3,
Terminate = 5,
Disarm = 6,
};
enum class command_after_quadchute : int32_t {
Warning_only = -1,
Return_mode = 0,
Land_mode = 1,
Hold_mode = 2,
};
// COM_RC_IN_MODE parameter values
enum class RcInMode : int32_t {
RcOnly = 0,
MavLinkOnly = 1,
RcOrMavlinkWithFallback = 2,
RcOrMavlinkKeepFirst = 3,
DisableManualControl = 4,
PriorityRcThenMavlinkAscending = 5,
PriorityMavlinkAscendingThenRc = 6,
PriorityRcThenMavlinkDescending = 7,
PriorityMavlinkDescendingThenRc = 8
};
enum class command_after_high_wind_failsafe : int32_t {
None = 0,
Warning = 1,
Hold_mode = 2,
Return_mode = 3,
Terminate = 4,
Land_mode = 5
};
enum class command_after_pos_low_failsafe : int32_t {
None = 0,
Warning = 1,
Hold_mode = 2,
Return_mode = 3,
Terminate = 4,
Land_mode = 5
};
enum class command_after_remaining_flight_time_low : int32_t {
None = 0,
Warning = 1,
Return_mode = 3
};
static ActionOptions fromNavDllOrRclActParam(int param_value);
static ActionOptions fromGfActParam(int param_value);
static ActionOptions fromImbalancedPropActParam(int param_value);
static ActionOptions fromActuatorFailureActParam(int param_value);
static ActionOptions fromBatteryWarningActParam(int param_value, uint8_t battery_warning);
static ActionOptions fromQuadchuteActParam(int param_value);
static Action fromOffboardLossActParam(int param_value, uint8_t &user_intended_mode);
static ActionOptions fromHighWindLimitActParam(int param_value);
static ActionOptions fromPosLowActParam(int param_value);
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
static bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);
const int _caller_id_mode_fallback{genCallerId()};
bool _last_state_mode_fallback{false};
const int _caller_id_mission_control_lost{genCallerId()};
bool _last_state_mission_control_lost{false};
const int _caller_id_battery_warning_low{genCallerId()}; ///< battery warning caller ID's: use different ID's as they have different actions
bool _last_state_battery_warning_low{false};
const int _caller_id_battery_warning_critical{genCallerId()};
bool _last_state_battery_warning_critical{false};
const int _caller_id_battery_warning_emergency{genCallerId()};
bool _last_state_battery_warning_emergency{false};
const int _caller_id_fd_esc_arming{genCallerId()};
bool _last_state_fd_esc_arming{false};
const int _caller_id_battery_unhealthy_spoolup{genCallerId()};
bool _last_state_battery_unhealthy_spoolup{false};
DEFINE_PARAMETERS_CUSTOM_PARENT(FailsafeBase,
(ParamInt<px4::params::NAV_DLL_ACT>) _param_nav_dll_act,
(ParamInt<px4::params::NAV_RCL_ACT>) _param_nav_rcl_act,
(ParamInt<px4::params::COM_RCL_EXCEPT>) _param_com_rcl_except,
(ParamInt<px4::params::COM_DLL_EXCEPT>) _param_com_dll_except,
(ParamInt<px4::params::COM_RC_IN_MODE>) _param_com_rc_in_mode,
(ParamInt<px4::params::GF_ACTION>) _param_gf_action,
(ParamFloat<px4::params::COM_SPOOLUP_TIME>) _param_com_spoolup_time,
(ParamInt<px4::params::COM_IMB_PROP_ACT>) _param_com_imb_prop_act,
(ParamFloat<px4::params::COM_LKDOWN_TKO>) _param_com_lkdown_tko,
(ParamInt<px4::params::CBRK_FLIGHTTERM>) _param_cbrk_flightterm,
(ParamInt<px4::params::COM_ACT_FAIL_ACT>) _param_com_actuator_failure_act,
(ParamInt<px4::params::COM_LOW_BAT_ACT>) _param_com_low_bat_act,
(ParamInt<px4::params::COM_OBL_RC_ACT>) _param_com_obl_rc_act,
(ParamInt<px4::params::COM_QC_ACT>) _param_com_qc_act,
(ParamInt<px4::params::COM_WIND_MAX_ACT>) _param_com_wind_max_act,
(ParamInt<px4::params::COM_FLTT_LOW_ACT>) _param_com_fltt_low_act,
(ParamInt<px4::params::COM_POS_LOW_ACT>) _param_com_pos_low_act
);
};