APM:Copter
land_detector.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // Code to detect a crash main ArduCopter code
4 #define LAND_CHECK_ANGLE_ERROR_DEG 30.0f // maximum angle error to be considered landing
5 #define LAND_CHECK_LARGE_ANGLE_CD 1500.0f // maximum angle target to be considered landing
6 #define LAND_CHECK_ACCEL_MOVING 3.0f // maximum acceleration after subtracting gravity
7 
8 
9 // counter to verify landings
10 static uint32_t land_detector_count = 0;
11 
12 // run land and crash detectors
13 // called at MAIN_LOOP_RATE
15 {
16  // update 1hz filtered acceleration
17  Vector3f accel_ef = ahrs.get_accel_ef_blended();
18  accel_ef.z += GRAVITY_MSS;
20 
22 
23 #if PARACHUTE == ENABLED
24  // check parachute
26 #endif
27 
28  crash_check();
29 }
30 
31 // update_land_detector - checks if we have landed and updates the ap.land_complete flag
32 // called at MAIN_LOOP_RATE
34 {
35  // land detector can not use the following sensors because they are unreliable during landing
36  // barometer altitude : ground effect can cause errors larger than 4m
37  // EKF vertical velocity or altitude : poor barometer and large acceleration from ground impact
38  // earth frame angle or angle error : landing on an uneven surface will force the airframe to match the ground angle
39  // gyro output : on uneven surface the airframe may rock back an forth after landing
40  // range finder : tend to be problematic at very short distances
41  // input throttle : in slow land the input throttle may be only slightly less than hover
42 
43  if (!motors->armed()) {
44  // if disarmed, always landed.
45  set_land_complete(true);
46  } else if (ap.land_complete) {
47 #if FRAME_CONFIG == HELI_FRAME
48  // if rotor speed and collective pitch are high then clear landing flag
49  if (motors->get_throttle() > get_non_takeoff_throttle() && !motors->limit.throttle_lower && motors->rotor_runup_complete()) {
50 #else
51  // if throttle output is high then clear landing flag
52  if (motors->get_throttle() > get_non_takeoff_throttle()) {
53 #endif
54  set_land_complete(false);
55  }
56  } else {
57 
58 #if FRAME_CONFIG == HELI_FRAME
59  // check that collective pitch is on lower limit (should be constrained by LAND_COL_MIN)
60  bool motor_at_lower_limit = motors->limit.throttle_lower;
61 #else
62  // check that the average throttle output is near minimum (less than 12.5% hover throttle)
63  bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();
64 #endif
65 
66  // check that the airframe is not accelerating (not falling or braking after fast forward flight)
67  bool accel_stationary = (land_accel_ef_filter.get().length() <= LAND_DETECTOR_ACCEL_MAX);
68 
69  // check that vertical speed is within 1m/s of zero
70  bool descent_rate_low = fabsf(inertial_nav.get_velocity_z()) < 100;
71 
72  // if we have a healthy rangefinder only allow landing detection below 2 meters
73  bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM);
74 
75  if (motor_at_lower_limit && accel_stationary && descent_rate_low && rangefinder_check) {
76  // landed criteria met - increment the counter and check if we've triggered
79  } else {
80  set_land_complete(true);
81  }
82  } else {
83  // we've sensed movement up or down so reset land_detector
85  }
86  }
87 
89 }
90 
91 // set land_complete flag and disarm motors if disarm-on-land is configured
93 {
94  // if no change, exit immediately
95  if( ap.land_complete == b )
96  return;
97 
99 
100  if(b){
102  } else {
104  }
105  ap.land_complete = b;
106 
107 #if STATS_ENABLED == ENABLED
108  g2.stats.set_flying(!b);
109 #endif
110 
111  // tell AHRS flying state
113 
114  // trigger disarm-on-land if configured
115  bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
116  const bool mode_disarms_on_land = flightmode->allows_arming(false) && !flightmode->has_manual_throttle();
117 
118  if (ap.land_complete && motors->armed() && disarm_on_land_configured && mode_disarms_on_land) {
120  }
121 }
122 
123 // set land complete maybe flag
125 {
126  // if no change, exit immediately
127  if (ap.land_complete_maybe == b)
128  return;
129 
130  if (b) {
132  }
133  ap.land_complete_maybe = b;
134 }
135 
136 // update_throttle_thr_mix - sets motors throttle_low_comp value depending upon vehicle state
137 // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
138 // has no effect when throttle is above hover throttle
140 {
141 #if FRAME_CONFIG != HELI_FRAME
142  // if disarmed or landed prioritise throttle
143  if(!motors->armed() || ap.land_complete) {
144  attitude_control->set_throttle_mix_min();
145  return;
146  }
147 
149  // manual throttle
150  if(channel_throttle->get_control_in() <= 0) {
151  attitude_control->set_throttle_mix_min();
152  } else {
153  attitude_control->set_throttle_mix_man();
154  }
155  } else {
156  // autopilot controlled throttle
157 
158  // check for aggressive flight requests - requested roll or pitch angle below 15 degrees
159  const Vector3f angle_target = attitude_control->get_att_target_euler_cd();
160  bool large_angle_request = (norm(angle_target.x, angle_target.y) > LAND_CHECK_LARGE_ANGLE_CD);
161 
162  // check for large external disturbance - angle error over 30 degrees
163  const float angle_error = attitude_control->get_att_error_angle_deg();
164  bool large_angle_error = (angle_error > LAND_CHECK_ANGLE_ERROR_DEG);
165 
166  // check for large acceleration - falling or high turbulence
167  Vector3f accel_ef = ahrs.get_accel_ef_blended();
168  accel_ef.z += GRAVITY_MSS;
169  bool accel_moving = (accel_ef.length() > LAND_CHECK_ACCEL_MOVING);
170 
171  // check for requested decent
172  bool descent_not_demanded = pos_control->get_desired_velocity().z >= 0.0f;
173 
174  if ( large_angle_request || large_angle_error || accel_moving || descent_not_demanded) {
175  attitude_control->set_throttle_mix_max();
176  } else {
177  attitude_control->set_throttle_mix_min();
178  }
179  }
180 #endif
181 }
float norm(const T first, const U second, const Params... parameters)
void update_land_detector()
float get_velocity_z() const
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
bool rangefinder_alt_ok()
Definition: sensors.cpp:69
const Vector3f & get_accel_ef_blended() const override
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
void crash_check()
Definition: crash_check.cpp:11
#define LAND_CHECK_ANGLE_ERROR_DEG
void set_land_complete_maybe(bool b)
#define LAND_DETECTOR_ACCEL_MAX
Definition: config.h:435
LowPassFilterVector3f land_accel_ef_filter
Definition: Copter.h:468
AP_Int16 throttle_behavior
Definition: Parameters.h:387
uint16_t get_loop_rate_hz(void)
void update_land_and_crash_detectors()
#define LAND_DETECTOR_MAYBE_TRIGGER_SEC
Definition: config.h:429
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
float get_loop_period_s()
void update_throttle_thr_mix()
struct Copter::@0 rangefinder_state
#define THR_BEHAVE_DISARM_ON_LAND_DETECT
Definition: defines.h:485
void parachute_check()
Definition: crash_check.cpp:63
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
void set_likely_flying(bool b)
MOTOR_CLASS * motors
Definition: Copter.h:422
static uint32_t land_detector_count
#define LAND_CHECK_LARGE_ANGLE_CD
#define DATA_NOT_LANDED
Definition: defines.h:344
RC_Channel * channel_throttle
Definition: Copter.h:223
int16_t get_control_in() const
void set_flying(bool b)
#define GRAVITY_MSS
Mode * flightmode
Definition: Copter.h:955
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
void set_land_complete(bool b)
const Vector3f & get() const
float length(void) const
#define DATA_LAND_COMPLETE_MAYBE
Definition: defines.h:342
AP_Scheduler scheduler
Definition: Copter.h:212
const Vector3f & get_desired_velocity()
Parameters g
Definition: Copter.h:208
AP_Stats stats
Definition: Parameters.h:508
AC_PosControl * pos_control
Definition: Copter.h:493
void init_disarm_motors()
Definition: motors.cpp:241
virtual bool has_manual_throttle() const =0
float get_non_takeoff_throttle()
Definition: Attitude.cpp:156
ParametersG2 g2
Definition: Copter.h:209
#define LAND_RANGEFINDER_MIN_ALT_CM
Definition: config.h:419
#define LAND_DETECTOR_TRIGGER_SEC
Definition: config.h:426
virtual bool allows_arming(bool from_gcs) const =0
#define LAND_CHECK_ACCEL_MOVING
#define DATA_LAND_COMPLETE
Definition: defines.h:343
Vector3f apply(Vector3f sample, float dt)