CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/is_flying.cpp
Views: 1798
1
#include "Plane.h"
2
3
#include <AP_Stats/AP_Stats.h> // statistics library
4
5
/*
6
is_flying and crash detection logic
7
*/
8
9
#define CRASH_DETECTION_DELAY_MS 500
10
#define IS_FLYING_IMPACT_TIMER_MS 3000
11
#define GPS_IS_FLYING_SPEED_CMS 150
12
13
/*
14
Do we think we are flying?
15
Probabilistic method where a bool is low-passed and considered a probability.
16
*/
17
void Plane::update_is_flying_5Hz(void)
18
{
19
float aspeed=0;
20
bool is_flying_bool = false;
21
uint32_t now_ms = AP_HAL::millis();
22
23
uint32_t ground_speed_thresh_cm = (aparm.min_groundspeed > 0) ? ((uint32_t)(aparm.min_groundspeed*(100*0.9))) : GPS_IS_FLYING_SPEED_CMS;
24
bool gps_confirmed_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_3D) &&
25
(gps.ground_speed_cm() >= ground_speed_thresh_cm);
26
27
// airspeed at least 75% of stall speed?
28
const float airspeed_threshold = MAX(aparm.airspeed_min,2)*0.75f;
29
bool airspeed_movement = ahrs.airspeed_estimate(aspeed) && (aspeed >= airspeed_threshold);
30
31
if (gps.status() < AP_GPS::GPS_OK_FIX_2D && arming.is_armed() && !airspeed_movement && isFlyingProbability > 0.3) {
32
// when flying with no GPS, use the last airspeed estimate to
33
// determine if we think we have airspeed movement. This
34
// prevents the crash detector from triggering when
35
// dead-reckoning under long GPS loss
36
airspeed_movement = aspeed >= airspeed_threshold;
37
}
38
39
#if HAL_QUADPLANE_ENABLED
40
is_flying_bool = quadplane.is_flying();
41
#endif
42
if (is_flying_bool) {
43
// no need to look further
44
} else if(arming.is_armed()) {
45
// when armed assuming flying and we need overwhelming evidence that we ARE NOT flying
46
// short drop-outs of GPS are common during flight due to banking which points the antenna in different directions
47
bool gps_lost_recently = (gps.last_fix_time_ms() > 0) && // we have locked to GPS before
48
(gps.status() < AP_GPS::GPS_OK_FIX_2D) && // and it's lost now
49
(now_ms - gps.last_fix_time_ms() < 5000); // but it wasn't that long ago (<5s)
50
51
if ((auto_state.last_flying_ms > 0) && gps_lost_recently) {
52
// we've flown before, remove GPS constraints temporarily and only use airspeed
53
is_flying_bool = airspeed_movement; // moving through the air
54
} else {
55
// Because ahrs.airspeed_estimate can return a continued high value after landing if flying in
56
// strong winds above stall speed it is necessary to include the IMU based movement check.
57
is_flying_bool = (airspeed_movement && !AP::ins().is_still()) || // moving through the air
58
gps_confirmed_movement; // locked and we're moving
59
}
60
61
if (control_mode == &mode_auto) {
62
/*
63
make is_flying() more accurate during various auto modes
64
*/
65
66
// Detect X-axis deceleration for probable ground impacts.
67
// Limit the max probability so it can decay faster. This
68
// will not change the is_flying state, anything above 0.1
69
// is "true", it just allows it to decay faster once we decide we
70
// aren't flying using the normal schemes
71
if (g.crash_accel_threshold == 0) {
72
crash_state.impact_detected = false;
73
} else if (ins.get_accel_peak_hold_neg_x() < -(g.crash_accel_threshold)) {
74
// large deceleration detected, lets lower confidence VERY quickly
75
crash_state.impact_detected = true;
76
crash_state.impact_timer_ms = now_ms;
77
if (isFlyingProbability > 0.2f) {
78
isFlyingProbability = 0.2f;
79
}
80
} else if (crash_state.impact_detected &&
81
(now_ms - crash_state.impact_timer_ms > IS_FLYING_IMPACT_TIMER_MS)) {
82
// no impacts seen in a while, clear the flag so we stop clipping isFlyingProbability
83
crash_state.impact_detected = false;
84
}
85
86
switch (flight_stage)
87
{
88
case AP_FixedWing::FlightStage::TAKEOFF:
89
break;
90
91
case AP_FixedWing::FlightStage::NORMAL:
92
if (in_preLaunch_flight_stage()) {
93
// while on the ground, an uncalibrated airspeed sensor can drift to 7m/s so
94
// ensure we aren't showing a false positive.
95
is_flying_bool = false;
96
crash_state.is_crashed = false;
97
auto_state.started_flying_in_auto_ms = 0;
98
}
99
break;
100
101
case AP_FixedWing::FlightStage::VTOL:
102
// TODO: detect ground impacts
103
break;
104
105
case AP_FixedWing::FlightStage::LAND:
106
if (landing.is_on_approach() && auto_state.sink_rate > 0.2f) {
107
is_flying_bool = true;
108
}
109
break;
110
111
case AP_FixedWing::FlightStage::ABORT_LANDING:
112
if (auto_state.sink_rate < -0.5f) {
113
// steep climb
114
is_flying_bool = true;
115
}
116
break;
117
118
default:
119
break;
120
} // switch
121
}
122
} else {
123
// when disarmed assume not flying and need overwhelming evidence that we ARE flying
124
is_flying_bool = airspeed_movement && gps_confirmed_movement;
125
126
if ((flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || landing.is_flaring()) {
127
is_flying_bool = false;
128
}
129
}
130
131
if (!crash_state.impact_detected || !is_flying_bool) {
132
// when impact is detected, enforce a clip. Only allow isFlyingProbability to go down, not up.
133
// low-pass the result.
134
// coef=0.15f @ 5Hz takes 3.0s to go from 100% down to 10% (or 0% up to 90%)
135
isFlyingProbability = (0.85f * isFlyingProbability) + (0.15f * (float)is_flying_bool);
136
}
137
138
/*
139
update last_flying_ms so we always know how long we have not
140
been flying for. This helps for crash detection and auto-disarm
141
*/
142
bool new_is_flying = is_flying();
143
144
// we are flying, note the time
145
if (new_is_flying) {
146
147
auto_state.last_flying_ms = now_ms;
148
149
if (!previous_is_flying) {
150
// just started flying in any mode
151
started_flying_ms = now_ms;
152
}
153
154
if ((control_mode == &mode_auto) &&
155
((auto_state.started_flying_in_auto_ms == 0) || !previous_is_flying) ) {
156
157
// We just started flying, note that time also
158
auto_state.started_flying_in_auto_ms = now_ms;
159
}
160
}
161
previous_is_flying = new_is_flying;
162
#if HAL_ADSB_ENABLED
163
adsb.set_is_flying(new_is_flying);
164
#endif
165
#if HAL_PARACHUTE_ENABLED
166
parachute.set_is_flying(new_is_flying);
167
#endif
168
#if AP_STATS_ENABLED
169
AP::stats()->set_flying(new_is_flying);
170
#endif
171
AP_Notify::flags.flying = new_is_flying;
172
173
crash_detection_update();
174
175
#if HAL_LOGGING_ENABLED
176
Log_Write_Status();
177
#endif
178
179
// tell AHRS flying state
180
set_likely_flying(new_is_flying);
181
182
// conservative ground mode value for rate D suppression
183
ground_mode = !is_flying() && !arming.is_armed_and_safety_off();
184
}
185
186
/*
187
return true if we think we are flying. This is a probabilistic
188
estimate, and needs to be used very carefully. Each use case needs
189
to be thought about individually.
190
*/
191
bool Plane::is_flying(void)
192
{
193
if (arming.is_armed_and_safety_off()) {
194
#if HAL_QUADPLANE_ENABLED
195
if (quadplane.is_flying_vtol()) {
196
return true;
197
}
198
#endif
199
// when armed, assume we're flying unless we probably aren't
200
return (isFlyingProbability >= 0.1f);
201
}
202
203
// when disarmed, assume we're not flying unless we probably are
204
return (isFlyingProbability >= 0.9f);
205
}
206
207
/*
208
* Determine if we have crashed
209
*/
210
void Plane::crash_detection_update(void)
211
{
212
if (control_mode != &mode_auto || !aparm.crash_detection_enable)
213
{
214
// crash detection is only available in AUTO mode
215
crash_state.debounce_timer_ms = 0;
216
crash_state.is_crashed = false;
217
return;
218
}
219
220
uint32_t now_ms = AP_HAL::millis();
221
bool crashed_near_land_waypoint = false;
222
bool crashed = false;
223
bool been_auto_flying = (auto_state.started_flying_in_auto_ms > 0) &&
224
(now_ms - auto_state.started_flying_in_auto_ms >= 2500);
225
226
if (!is_flying() && arming.is_armed())
227
{
228
if (landing.is_expecting_impact()) {
229
// We should be nice and level-ish in this flight stage. If not, we most
230
// likely had a crazy landing. Throttle is inhibited already at the flare
231
// but go ahead and notify GCS and perform any additional post-crash actions.
232
// Declare a crash if we are oriented more that 60deg in pitch or roll
233
if (!crash_state.checkedHardLanding && // only check once
234
been_auto_flying &&
235
(labs(ahrs.roll_sensor) > 6000 || labs(ahrs.pitch_sensor) > 6000)) {
236
237
crashed = true;
238
239
// did we "crash" within 75m of the landing location? Probably just a hard landing
240
crashed_near_land_waypoint =
241
current_loc.get_distance(mission.get_current_nav_cmd().content.location) < 75;
242
243
// trigger hard landing event right away, or never again. This inhibits a false hard landing
244
// event when, for example, a minute after a good landing you pick the plane up and
245
// this logic is still running and detects the plane is on its side as you carry it.
246
crash_state.debounce_timer_ms = now_ms;
247
crash_state.debounce_time_total_ms = 0; // no debounce
248
}
249
250
crash_state.checkedHardLanding = true;
251
252
} else if (landing.is_on_approach()) {
253
// when altitude gets low, we automatically flare so ground crashes
254
// most likely can not be triggered from here. However,
255
// a crash into a tree would be caught here.
256
if (been_auto_flying) {
257
crashed = true;
258
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
259
}
260
261
} else {
262
switch (flight_stage)
263
{
264
case AP_FixedWing::FlightStage::TAKEOFF:
265
if (g.takeoff_throttle_min_accel > 0 &&
266
!throttle_suppressed) {
267
// if you have an acceleration holding back throttle, but you met the
268
// accel threshold but still not flying, then you either shook/hit the
269
// plane or it was a failed launch.
270
crashed = true;
271
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
272
}
273
// TODO: handle auto missions without NAV_TAKEOFF mission cmd
274
break;
275
276
case AP_FixedWing::FlightStage::NORMAL:
277
if (!in_preLaunch_flight_stage() && been_auto_flying) {
278
crashed = true;
279
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
280
}
281
break;
282
283
case AP_FixedWing::FlightStage::VTOL:
284
// we need a totally new method for this
285
crashed = false;
286
break;
287
288
default:
289
break;
290
} // switch
291
}
292
} else {
293
crash_state.checkedHardLanding = false;
294
}
295
296
// if we have no GPS lock and we don't have a functional airspeed
297
// sensor then don't do crash detection
298
if (gps.status() < AP_GPS::GPS_OK_FIX_3D) {
299
#if AP_AIRSPEED_ENABLED
300
if (!airspeed.use() || !airspeed.healthy()) {
301
crashed = false;
302
}
303
#else
304
crashed = false;
305
#endif
306
}
307
308
if (!crashed) {
309
// reset timer
310
crash_state.debounce_timer_ms = 0;
311
312
} else if (crash_state.debounce_timer_ms == 0) {
313
// start timer
314
crash_state.debounce_timer_ms = now_ms;
315
316
} else if ((now_ms - crash_state.debounce_timer_ms >= crash_state.debounce_time_total_ms) && !crash_state.is_crashed) {
317
crash_state.is_crashed = true;
318
if (aparm.crash_detection_enable & CRASH_DETECT_ACTION_BITMASK_DISARM) {
319
arming.disarm(AP_Arming::Method::CRASH);
320
}
321
if (crashed_near_land_waypoint) {
322
gcs().send_text(MAV_SEVERITY_CRITICAL, "Hard landing detected");
323
} else {
324
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Crash detected");
325
}
326
}
327
}
328
329
/*
330
* return true if we are in a pre-launch phase of an auto-launch, typically used in bungee launches
331
*/
332
bool Plane::in_preLaunch_flight_stage(void)
333
{
334
if (control_mode == &mode_takeoff && throttle_suppressed) {
335
return true;
336
}
337
#if HAL_QUADPLANE_ENABLED
338
if (quadplane.is_vtol_takeoff(mission.get_current_nav_cmd().id)) {
339
return false;
340
}
341
#endif
342
return (control_mode == &mode_auto &&
343
throttle_suppressed &&
344
flight_stage == AP_FixedWing::FlightStage::NORMAL &&
345
mission.get_current_nav_cmd().id == MAV_CMD_NAV_TAKEOFF);
346
}
347
348