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/ArduCopter/land_detector.cpp
Views: 1798
1
#include "Copter.h"
2
3
#include <AP_Stats/AP_Stats.h> // statistics library
4
5
// Code to detect a crash main ArduCopter code
6
#define LAND_CHECK_ANGLE_ERROR_DEG 30.0f // maximum angle error to be considered landing
7
#define LAND_CHECK_LARGE_ANGLE_CD 1500.0f // maximum angle target to be considered landing
8
#define LAND_CHECK_ACCEL_MOVING 3.0f // maximum acceleration after subtracting gravity
9
10
11
// counter to verify landings
12
static uint32_t land_detector_count = 0;
13
14
// run land and crash detectors
15
// called at MAIN_LOOP_RATE
16
void Copter::update_land_and_crash_detectors()
17
{
18
// update 1hz filtered acceleration
19
Vector3f accel_ef = ahrs.get_accel_ef();
20
accel_ef.z += GRAVITY_MSS;
21
land_accel_ef_filter.apply(accel_ef, scheduler.get_loop_period_s());
22
23
update_land_detector();
24
25
#if HAL_PARACHUTE_ENABLED
26
// check parachute
27
parachute_check();
28
#endif
29
30
crash_check();
31
thrust_loss_check();
32
yaw_imbalance_check();
33
}
34
35
// update_land_detector - checks if we have landed and updates the ap.land_complete flag
36
// called at MAIN_LOOP_RATE
37
void Copter::update_land_detector()
38
{
39
// land detector can not use the following sensors because they are unreliable during landing
40
// barometer altitude : ground effect can cause errors larger than 4m
41
// EKF vertical velocity or altitude : poor barometer and large acceleration from ground impact
42
// earth frame angle or angle error : landing on an uneven surface will force the airframe to match the ground angle
43
// gyro output : on uneven surface the airframe may rock back an forth after landing
44
// range finder : tend to be problematic at very short distances
45
// input throttle : in slow land the input throttle may be only slightly less than hover
46
47
#if HAL_LOGGING_ENABLED
48
uint16_t logging_flags = 0;
49
#define SET_LOG_FLAG(condition, flag) if (condition) { logging_flags |= (uint16_t)flag; }
50
#else
51
#define SET_LOG_FLAG(condition, flag)
52
#endif
53
54
if (!motors->armed()) {
55
// if disarmed, always landed.
56
set_land_complete(true);
57
} else if (ap.land_complete) {
58
#if FRAME_CONFIG == HELI_FRAME
59
// if rotor speed and collective pitch are high then clear landing flag
60
if (!flightmode->is_taking_off() && motors->get_takeoff_collective() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
61
#else
62
// if throttle output is high then clear landing flag
63
if (!flightmode->is_taking_off() && motors->get_throttle_out() > get_non_takeoff_throttle() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
64
// this should never happen because take-off should be detected at the flight mode level
65
// this here to highlight there is a bug or missing take-off detection
66
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
67
#endif
68
set_land_complete(false);
69
}
70
} else if (standby_active) {
71
// land detector will not run in standby mode
72
land_detector_count = 0;
73
} else {
74
75
float land_trigger_sec = LAND_DETECTOR_TRIGGER_SEC;
76
#if FRAME_CONFIG == HELI_FRAME
77
// check for both manual collective modes and modes that use altitude hold. For manual collective (called throttle
78
// because multi's use throttle), check that collective pitch is below land min collective position or throttle stick is zero.
79
// Including the throttle zero check will ensure the conditions where stabilize stick zero position was not below collective min. For modes
80
// that use altitude hold, check that the pilot is commanding a descent and collective is at min allowed for altitude hold modes.
81
82
// check if landing
83
const bool landing = flightmode->is_landing();
84
SET_LOG_FLAG(landing, LandDetectorLoggingFlag::LANDING);
85
bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f)
86
#if MODE_AUTOROTATE_ENABLED
87
|| (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll())
88
#endif
89
|| ((!get_force_flying() || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f);
90
bool throttle_mix_at_min = true;
91
#else
92
// check that the average throttle output is near minimum (less than 12.5% hover throttle)
93
bool motor_at_lower_limit = motors->limit.throttle_lower;
94
bool throttle_mix_at_min = attitude_control->is_throttle_mix_min();
95
// set throttle_mix_at_min to true because throttle is never at mix min in airmode
96
// increase land_trigger_sec when using airmode
97
if (flightmode->has_manual_throttle() && air_mode == AirMode::AIRMODE_ENABLED) {
98
land_trigger_sec = LAND_AIRMODE_DETECTOR_TRIGGER_SEC;
99
throttle_mix_at_min = true;
100
}
101
#endif
102
SET_LOG_FLAG(motor_at_lower_limit, LandDetectorLoggingFlag::MOTOR_AT_LOWER_LIMIT);
103
SET_LOG_FLAG(throttle_mix_at_min, LandDetectorLoggingFlag::THROTTLE_MIX_AT_MIN);
104
105
uint8_t land_detector_scalar = 1;
106
#if AP_LANDINGGEAR_ENABLED
107
if (landinggear.get_wow_state() != AP_LandingGear::LG_WOW_UNKNOWN) {
108
// we have a WoW sensor so lets loosen the strictness of the landing detector
109
land_detector_scalar = 2;
110
}
111
#endif
112
113
// check for aggressive flight requests - requested roll or pitch angle below 15 degrees
114
const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
115
bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD;
116
SET_LOG_FLAG(large_angle_request, LandDetectorLoggingFlag::LARGE_ANGLE_REQUEST);
117
118
// check for large external disturbance - angle error over 30 degrees
119
const float angle_error = attitude_control->get_att_error_angle_deg();
120
bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG);
121
SET_LOG_FLAG(large_angle_error, LandDetectorLoggingFlag::LARGE_ANGLE_ERROR);
122
123
// check that the airframe is not accelerating (not falling or braking after fast forward flight)
124
bool accel_stationary = (land_accel_ef_filter.get().length() <= LAND_DETECTOR_ACCEL_MAX * land_detector_scalar);
125
SET_LOG_FLAG(accel_stationary, LandDetectorLoggingFlag::ACCEL_STATIONARY);
126
127
// check that vertical speed is within 1m/s of zero
128
bool descent_rate_low = fabsf(inertial_nav.get_velocity_z_up_cms()) < 100.0 * LAND_DETECTOR_VEL_Z_MAX * land_detector_scalar;
129
SET_LOG_FLAG(descent_rate_low, LandDetectorLoggingFlag::DESCENT_RATE_LOW);
130
131
// if we have a healthy rangefinder only allow landing detection below 2 meters
132
bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM);
133
SET_LOG_FLAG(rangefinder_check, LandDetectorLoggingFlag::RANGEFINDER_BELOW_2M);
134
135
// if we have weight on wheels (WoW) or ambiguous unknown. never no WoW
136
#if AP_LANDINGGEAR_ENABLED
137
const bool WoW_check = (landinggear.get_wow_state() == AP_LandingGear::LG_WOW || landinggear.get_wow_state() == AP_LandingGear::LG_WOW_UNKNOWN);
138
#else
139
const bool WoW_check = true;
140
#endif
141
SET_LOG_FLAG(WoW_check, LandDetectorLoggingFlag::WOW);
142
143
if (motor_at_lower_limit && throttle_mix_at_min && !large_angle_request && !large_angle_error && accel_stationary && descent_rate_low && rangefinder_check && WoW_check) {
144
// landed criteria met - increment the counter and check if we've triggered
145
if( land_detector_count < land_trigger_sec*scheduler.get_loop_rate_hz()) {
146
land_detector_count++;
147
} else {
148
set_land_complete(true);
149
}
150
} else {
151
// we've sensed movement up or down so reset land_detector
152
land_detector_count = 0;
153
}
154
}
155
156
set_land_complete_maybe(ap.land_complete || (land_detector_count >= LAND_DETECTOR_MAYBE_TRIGGER_SEC*scheduler.get_loop_rate_hz()));
157
158
#if HAL_LOGGING_ENABLED
159
// @LoggerMessage: LDET
160
// @Description: Land Detector State
161
// @Field: TimeUS: Time since system startup
162
// @Field: Flags: boolean state flags
163
// @FieldBitmaskEnum: Flags: Copter::LandDetectorLoggingFlag
164
// @Field: Count: landing_detector pass count
165
SET_LOG_FLAG(ap.land_complete, LandDetectorLoggingFlag::LANDED);
166
SET_LOG_FLAG(ap.land_complete_maybe, LandDetectorLoggingFlag::LANDED_MAYBE);
167
SET_LOG_FLAG(standby_active, LandDetectorLoggingFlag::STANDBY_ACTIVE);
168
Log_LDET(logging_flags, land_detector_count);
169
#undef SET_LOG_FLAG
170
#endif
171
}
172
173
#if HAL_LOGGING_ENABLED
174
void Copter::Log_LDET(uint16_t logging_flags, uint32_t detector_count)
175
{
176
// do not log if no change:
177
if (logging_flags == land_detector.last_logged_flags &&
178
detector_count == land_detector.last_logged_count) {
179
return;
180
}
181
// do not log more than 50Hz:
182
const auto now = AP_HAL::millis();
183
if (now - land_detector.last_logged_ms < 20) {
184
return;
185
}
186
187
land_detector.last_logged_count = detector_count;
188
land_detector.last_logged_flags = logging_flags;
189
land_detector.last_logged_ms = now;
190
191
AP::logger().WriteStreaming(
192
"LDET",
193
"TimeUS," "Flags," "Count",
194
"s" "-" "-",
195
"F" "-" "-",
196
"Q" "H" "I",
197
AP_HAL::micros64(),
198
logging_flags,
199
land_detector_count
200
);
201
}
202
#endif
203
204
// set land_complete flag and disarm motors if disarm-on-land is configured
205
void Copter::set_land_complete(bool b)
206
{
207
// if no change, exit immediately
208
if( ap.land_complete == b )
209
return;
210
211
land_detector_count = 0;
212
213
#if HAL_LOGGING_ENABLED
214
if(b){
215
AP::logger().Write_Event(LogEvent::LAND_COMPLETE);
216
} else {
217
AP::logger().Write_Event(LogEvent::NOT_LANDED);
218
}
219
#endif
220
ap.land_complete = b;
221
222
#if AP_STATS_ENABLED
223
AP::stats()->set_flying(!b);
224
#endif
225
226
// tell AHRS flying state
227
set_likely_flying(!b);
228
229
if (!b) {
230
// not landed, no further action
231
return;
232
}
233
234
// landed; trigger disarm-on-land if configured
235
if ((g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) == 0) {
236
// not configured to disarm on landing detection
237
return;
238
}
239
240
if (!motors->armed()) {
241
// we are not currently armed, so we don't need to disarm:
242
// n.b. should this be checking vehicle-armed rather than motors-armed?
243
return;
244
}
245
246
if (flightmode->has_manual_throttle()) {
247
// we do not use the landing detector to disarm if the vehicle
248
// is in e.g. STABILIZE. The normal DISARM_DELAY logic applies.
249
return;
250
}
251
252
// the flightmode may not allow disarm on landing. Note that this
253
// check returns false for the LAND flight mode - it checks the
254
// landing detector (ap.land_complete) itself.
255
if (!flightmode->allows_arming(AP_Arming::Method::LANDING)) {
256
return;
257
}
258
259
// all checks passed, disarm the vehicle:
260
arming.disarm(AP_Arming::Method::LANDED);
261
}
262
263
// set land complete maybe flag
264
void Copter::set_land_complete_maybe(bool b)
265
{
266
// if no change, exit immediately
267
if (ap.land_complete_maybe == b)
268
return;
269
270
if (b) {
271
LOGGER_WRITE_EVENT(LogEvent::LAND_COMPLETE_MAYBE);
272
}
273
ap.land_complete_maybe = b;
274
}
275
276
// sets motors throttle_low_comp value depending upon vehicle state
277
// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
278
// has no effect when throttle is above hover throttle
279
void Copter::update_throttle_mix()
280
{
281
#if FRAME_CONFIG != HELI_FRAME
282
// if disarmed or landed prioritise throttle
283
if (!motors->armed() || ap.land_complete) {
284
attitude_control->set_throttle_mix_min();
285
return;
286
}
287
288
if (flightmode->has_manual_throttle()) {
289
// manual throttle
290
if (channel_throttle->get_control_in() <= 0 && air_mode != AirMode::AIRMODE_ENABLED) {
291
attitude_control->set_throttle_mix_min();
292
} else {
293
attitude_control->set_throttle_mix_man();
294
}
295
} else {
296
// autopilot controlled throttle
297
298
// check for aggressive flight requests - requested roll or pitch angle below 15 degrees
299
const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
300
bool large_angle_request = angle_target.xy().length() > LAND_CHECK_LARGE_ANGLE_CD;
301
302
// check for large external disturbance - angle error over 30 degrees
303
const float angle_error = attitude_control->get_att_error_angle_deg();
304
bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG);
305
306
// check for large acceleration - falling or high turbulence
307
const bool accel_moving = (land_accel_ef_filter.get().length() > LAND_CHECK_ACCEL_MOVING);
308
309
// check for requested descent
310
bool descent_not_demanded = pos_control->get_vel_desired_cms().z >= 0.0f;
311
312
// check if landing
313
const bool landing = flightmode->is_landing();
314
315
if (((large_angle_request || get_force_flying()) && !landing) || large_angle_error || accel_moving || descent_not_demanded) {
316
attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio());
317
} else {
318
attitude_control->set_throttle_mix_min();
319
}
320
}
321
#endif
322
}
323
324
// helper function for force flying flag
325
bool Copter::get_force_flying() const
326
{
327
#if FRAME_CONFIG == HELI_FRAME
328
if (attitude_control->get_inverted_flight()) {
329
return true;
330
}
331
#endif
332
return force_flying;
333
}
334
335