Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/events.cpp
9448 views
1
#include "Plane.h"
2
3
// returns true if the vehicle is in landing sequence. Intended only
4
// for use in failsafe code.
5
bool Plane::failsafe_in_landing_sequence() const
6
{
7
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
8
return true;
9
}
10
#if HAL_QUADPLANE_ENABLED
11
if (quadplane.in_vtol_land_sequence()) {
12
return true;
13
}
14
#endif
15
if (mission.get_in_landing_sequence_flag()) {
16
return true;
17
}
18
return false;
19
}
20
21
void Plane::rc_failsafe_short_on_event()
22
{
23
// This is how to handle a short loss of control signal failsafe.
24
failsafe.state = FAILSAFE_SHORT;
25
failsafe.saved_mode_number = control_mode->mode_number();
26
switch (control_mode->mode_number())
27
{
28
case Mode::Number::MANUAL:
29
case Mode::Number::STABILIZE:
30
case Mode::Number::ACRO:
31
case Mode::Number::FLY_BY_WIRE_A:
32
case Mode::Number::AUTOTUNE:
33
case Mode::Number::FLY_BY_WIRE_B:
34
case Mode::Number::CRUISE:
35
case Mode::Number::TRAINING:
36
if(plane.emergency_landing) {
37
set_mode(mode_fbwa, ModeReason::RADIO_FAILSAFE); // emergency landing switch overrides normal action to allow out of range landing
38
break;
39
}
40
if(g.fs_action_short == FS_ACTION_SHORT_FBWA) {
41
set_mode(mode_fbwa, ModeReason::RADIO_FAILSAFE);
42
} else if (g.fs_action_short == FS_ACTION_SHORT_FBWB) {
43
set_mode(mode_fbwb, ModeReason::RADIO_FAILSAFE);
44
} else {
45
set_mode(mode_circle, ModeReason::RADIO_FAILSAFE); // circle if action = 0 or 1
46
}
47
break;
48
49
#if HAL_QUADPLANE_ENABLED
50
case Mode::Number::QSTABILIZE:
51
case Mode::Number::QLOITER:
52
case Mode::Number::QHOVER:
53
#if QAUTOTUNE_ENABLED
54
case Mode::Number::QAUTOTUNE:
55
#endif
56
case Mode::Number::QACRO:
57
if (quadplane.option_is_set(QuadPlane::Option::FS_RTL)) {
58
set_mode(mode_rtl, ModeReason::RADIO_FAILSAFE);
59
} else if (quadplane.option_is_set(QuadPlane::Option::FS_QRTL)) {
60
set_mode(mode_qrtl, ModeReason::RADIO_FAILSAFE);
61
} else {
62
set_mode(mode_qland, ModeReason::RADIO_FAILSAFE);
63
}
64
break;
65
#endif // HAL_QUADPLANE_ENABLED
66
67
case Mode::Number::AUTO:
68
#if MODE_AUTOLAND_ENABLED
69
case Mode::Number::AUTOLAND:
70
#endif
71
{
72
if (failsafe_in_landing_sequence()) {
73
// don't failsafe in a landing sequence
74
break;
75
}
76
FALLTHROUGH;
77
}
78
case Mode::Number::AVOID_ADSB:
79
case Mode::Number::GUIDED:
80
case Mode::Number::LOITER:
81
case Mode::Number::THERMAL:
82
if (g.fs_action_short != FS_ACTION_SHORT_BESTGUESS) { // if acton = 0(BESTGUESS) this group of modes take no action
83
failsafe.saved_mode_number = control_mode->mode_number();
84
if (g.fs_action_short == FS_ACTION_SHORT_FBWA) {
85
set_mode(mode_fbwa, ModeReason::RADIO_FAILSAFE);
86
} else if (g.fs_action_short == FS_ACTION_SHORT_FBWB) {
87
set_mode(mode_fbwb, ModeReason::RADIO_FAILSAFE);
88
} else {
89
set_mode(mode_circle, ModeReason::RADIO_FAILSAFE);
90
}
91
}
92
break;
93
case Mode::Number::CIRCLE: // these modes never take any short failsafe action and continue
94
case Mode::Number::TAKEOFF:
95
case Mode::Number::RTL:
96
#if HAL_QUADPLANE_ENABLED
97
case Mode::Number::QLAND:
98
case Mode::Number::QRTL:
99
case Mode::Number::LOITER_ALT_QLAND:
100
#endif
101
case Mode::Number::INITIALISING:
102
break;
103
}
104
if (failsafe.saved_mode_number != control_mode->mode_number()) {
105
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe: switched to %s", control_mode->name());
106
} else {
107
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe On");
108
}
109
}
110
111
void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason)
112
{
113
114
if (reason == ModeReason::GCS_FAILSAFE) {
115
AP_Notify::flags.failsafe_gcs = true;
116
}
117
118
// This is how to handle a long loss of control signal failsafe.
119
// If the GCS is locked up we allow control to revert to RC
120
RC_Channels::clear_overrides();
121
failsafe.state = fstype;
122
switch (control_mode->mode_number())
123
{
124
case Mode::Number::MANUAL:
125
case Mode::Number::STABILIZE:
126
case Mode::Number::ACRO:
127
case Mode::Number::FLY_BY_WIRE_A:
128
case Mode::Number::AUTOTUNE:
129
case Mode::Number::FLY_BY_WIRE_B:
130
case Mode::Number::CRUISE:
131
case Mode::Number::TRAINING:
132
case Mode::Number::CIRCLE:
133
case Mode::Number::LOITER:
134
case Mode::Number::THERMAL:
135
case Mode::Number::TAKEOFF:
136
if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF && !(g.fs_action_long == FS_ACTION_LONG_GLIDE || g.fs_action_long == FS_ACTION_LONG_PARACHUTE)) {
137
// don't failsafe if in initial climb of TAKEOFF mode and FS action is not parachute or glide
138
// long failsafe will be re-called if still in fs after initial climb
139
long_failsafe_pending = true;
140
break;
141
}
142
143
if(plane.emergency_landing) {
144
set_mode(mode_fbwa, reason); // emergency landing switch overrides normal action to allow out of range landing
145
break;
146
}
147
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
148
#if HAL_PARACHUTE_ENABLED
149
parachute_release();
150
#endif
151
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
152
set_mode(mode_fbwa, reason);
153
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
154
set_mode(mode_auto, reason);
155
#if MODE_AUTOLAND_ENABLED
156
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
157
if (!set_mode(mode_autoland, reason)) {
158
set_mode(mode_rtl, reason);
159
}
160
#endif
161
} else {
162
set_mode(mode_rtl, reason);
163
}
164
break;
165
166
#if HAL_QUADPLANE_ENABLED
167
case Mode::Number::QSTABILIZE:
168
case Mode::Number::QHOVER:
169
case Mode::Number::QLOITER:
170
case Mode::Number::QACRO:
171
#if QAUTOTUNE_ENABLED
172
case Mode::Number::QAUTOTUNE:
173
#endif
174
if (quadplane.option_is_set(QuadPlane::Option::FS_RTL)) {
175
set_mode(mode_rtl, reason);
176
} else if (quadplane.option_is_set(QuadPlane::Option::FS_QRTL)) {
177
set_mode(mode_qrtl, reason);
178
} else {
179
set_mode(mode_qland, reason);
180
}
181
break;
182
#endif // HAL_QUADPLANE_ENABLED
183
184
case Mode::Number::AUTO:
185
if (failsafe_in_landing_sequence()) {
186
// don't failsafe in a landing sequence
187
break;
188
}
189
190
#if HAL_QUADPLANE_ENABLED
191
if (quadplane.in_vtol_takeoff()) {
192
set_mode(mode_qland, reason);
193
// QLAND if in VTOL takeoff
194
break;
195
}
196
#endif
197
FALLTHROUGH;
198
199
case Mode::Number::AVOID_ADSB:
200
case Mode::Number::GUIDED:
201
202
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
203
#if HAL_PARACHUTE_ENABLED
204
parachute_release();
205
#endif
206
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
207
set_mode(mode_fbwa, reason);
208
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
209
set_mode(mode_auto, reason);
210
#if MODE_AUTOLAND_ENABLED
211
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
212
if (!set_mode(mode_autoland, reason)) {
213
set_mode(mode_rtl, reason);
214
}
215
#endif
216
} else if (g.fs_action_long == FS_ACTION_LONG_RTL) {
217
set_mode(mode_rtl, reason);
218
}
219
break;
220
case Mode::Number::RTL:
221
if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
222
set_mode(mode_auto, reason);
223
#if MODE_AUTOLAND_ENABLED
224
} else if (g.fs_action_long == FS_ACTION_LONG_AUTOLAND) {
225
set_mode(mode_autoland, reason);
226
#endif
227
}
228
break;
229
#if HAL_QUADPLANE_ENABLED
230
case Mode::Number::QLAND:
231
case Mode::Number::QRTL:
232
case Mode::Number::LOITER_ALT_QLAND:
233
#endif
234
case Mode::Number::INITIALISING:
235
#if MODE_AUTOLAND_ENABLED
236
case Mode::Number::AUTOLAND:
237
#endif
238
break;
239
}
240
gcs().send_text(MAV_SEVERITY_WARNING, "%s Failsafe On: switched to %s", (reason == ModeReason:: GCS_FAILSAFE) ? "GCS" : "RC Long", control_mode->name());
241
}
242
243
void Plane::rc_failsafe_short_off_event()
244
{
245
// We're back in radio contact
246
gcs().send_text(MAV_SEVERITY_WARNING, "RC Short Failsafe Cleared");
247
failsafe.state = FAILSAFE_NONE;
248
// restore entry mode if desired but check that our current mode is still due to failsafe
249
if (control_mode_reason == ModeReason::RADIO_FAILSAFE) {
250
set_mode_by_number(failsafe.saved_mode_number, ModeReason::RADIO_FAILSAFE_RECOVERY);
251
gcs().send_text(MAV_SEVERITY_INFO,"Flight mode %s restored",control_mode->name());
252
}
253
}
254
255
void Plane::failsafe_long_off_event(ModeReason reason)
256
{
257
long_failsafe_pending = false;
258
// We're back in radio contact with RC or GCS
259
if (reason == ModeReason:: GCS_FAILSAFE) {
260
AP_Notify::flags.failsafe_gcs = false;
261
gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Cleared");
262
}
263
else {
264
gcs().send_text(MAV_SEVERITY_WARNING, "RC Long Failsafe Cleared");
265
}
266
failsafe.state = FAILSAFE_NONE;
267
}
268
269
void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
270
{
271
switch ((Failsafe_Action)action) {
272
#if HAL_QUADPLANE_ENABLED
273
case Failsafe_Action_Loiter_alt_QLand:
274
if (quadplane.available()) {
275
plane.set_mode(mode_loiter_qland, ModeReason::BATTERY_FAILSAFE);
276
break;
277
}
278
FALLTHROUGH;
279
280
case Failsafe_Action_QLand:
281
if (quadplane.available()) {
282
plane.set_mode(mode_qland, ModeReason::BATTERY_FAILSAFE);
283
break;
284
}
285
FALLTHROUGH;
286
#endif // HAL_QUADPLANE_ENABLED
287
case Failsafe_Action_Land: {
288
bool already_landing = flight_stage == AP_FixedWing::FlightStage::LAND;
289
#if HAL_QUADPLANE_ENABLED
290
if (control_mode == &mode_qland || control_mode == &mode_loiter_qland) {
291
already_landing = true;
292
}
293
#endif
294
if (!already_landing && plane.have_position) {
295
// never stop a landing if we were already committed
296
if (plane.mission.is_best_land_sequence(plane.current_loc)) {
297
// continue mission as it will reach a landing in less distance
298
plane.mission.set_in_landing_sequence_flag(true);
299
break;
300
}
301
if (plane.mission.jump_to_landing_sequence(plane.current_loc)) {
302
plane.set_mode(mode_auto, ModeReason::BATTERY_FAILSAFE);
303
break;
304
}
305
}
306
FALLTHROUGH;
307
}
308
case Failsafe_Action_RTL:
309
case Failsafe_Action_AUTOLAND_OR_RTL: {
310
bool already_landing = flight_stage == AP_FixedWing::FlightStage::LAND;
311
#if HAL_QUADPLANE_ENABLED
312
if (control_mode == &mode_qland || control_mode == &mode_loiter_qland ||
313
quadplane.in_vtol_land_sequence()) {
314
already_landing = true;
315
}
316
#endif
317
#if MODE_AUTOLAND_ENABLED
318
if (control_mode == &mode_autoland) {
319
already_landing = true;
320
}
321
#endif
322
if (!already_landing) {
323
// never stop a landing if we were already committed
324
if ((g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START) && plane.have_position && plane.mission.is_best_land_sequence(plane.current_loc)) {
325
// continue mission as it will reach a landing in less distance
326
plane.mission.set_in_landing_sequence_flag(true);
327
break;
328
}
329
aparm.throttle_cruise.load();
330
#if MODE_AUTOLAND_ENABLED
331
if (((Failsafe_Action)action == Failsafe_Action_AUTOLAND_OR_RTL) && set_mode(mode_autoland, ModeReason::BATTERY_FAILSAFE)) {
332
break;
333
}
334
#endif
335
set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE);
336
}
337
break;
338
}
339
340
case Failsafe_Action_Terminate:
341
#if AP_ADVANCEDFAILSAFE_ENABLED
342
char battery_type_str[17];
343
snprintf(battery_type_str, 17, "%s battery", type_str);
344
afs.gcs_terminate(true, battery_type_str);
345
#else
346
arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE);
347
#endif
348
break;
349
350
case Failsafe_Action_Parachute:
351
#if HAL_PARACHUTE_ENABLED
352
parachute_release();
353
#endif
354
break;
355
356
case Failsafe_Action_None:
357
// don't actually do anything, however we should still flag the system as having hit a failsafe
358
// and ensure all appropriate flags are going off to the user
359
break;
360
}
361
}
362
363