APM:Copter
baro_ground_effect.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
4 {
5  if(!g2.gndeffect_comp_enabled || !motors->armed()) {
6  // disarmed - disable ground effect and return
7  gndeffect_state.takeoff_expected = false;
8  gndeffect_state.touchdown_expected = false;
9  ahrs.setTakeoffExpected(gndeffect_state.takeoff_expected);
10  ahrs.setTouchdownExpected(gndeffect_state.touchdown_expected);
11  return;
12  }
13 
14  // variable initialization
15  uint32_t tnow_ms = millis();
16  float xy_des_speed_cms = 0.0f;
17  float xy_speed_cms = 0.0f;
18  float des_climb_rate_cms = pos_control->get_desired_velocity().z;
19 
20  if (pos_control->is_active_xy()) {
21  Vector3f vel_target = pos_control->get_vel_target();
22  vel_target.z = 0.0f;
23  xy_des_speed_cms = vel_target.length();
24  }
25 
26  if (position_ok() || optflow_position_ok()) {
28  vel.z = 0.0f;
29  xy_speed_cms = vel.length();
30  }
31 
32  // takeoff logic
33 
34  // if we are armed and haven't yet taken off
35  if (motors->armed() && ap.land_complete && !gndeffect_state.takeoff_expected) {
36  gndeffect_state.takeoff_expected = true;
37  }
38 
39  // if we aren't taking off yet, reset the takeoff timer, altitude and complete flag
40  const bool throttle_up = flightmode->has_manual_throttle() && channel_throttle->get_control_in() > 0;
41  if (!throttle_up && ap.land_complete) {
42  gndeffect_state.takeoff_time_ms = tnow_ms;
43  gndeffect_state.takeoff_alt_cm = inertial_nav.get_altitude();
44  }
45 
46  // if we are in takeoff_expected and we meet the conditions for having taken off
47  // end the takeoff_expected state
48  if (gndeffect_state.takeoff_expected && (tnow_ms-gndeffect_state.takeoff_time_ms > 5000 || inertial_nav.get_altitude()-gndeffect_state.takeoff_alt_cm > 50.0f)) {
49  gndeffect_state.takeoff_expected = false;
50  }
51 
52  // landing logic
53  Vector3f angle_target_rad = attitude_control->get_att_target_euler_cd() * radians(0.01f);
54  bool small_angle_request = cosf(angle_target_rad.x)*cosf(angle_target_rad.y) > cosf(radians(7.5f));
55  bool xy_speed_low = (position_ok() || optflow_position_ok()) && xy_speed_cms <= 125.0f;
56  bool xy_speed_demand_low = pos_control->is_active_xy() && xy_des_speed_cms <= 125.0f;
57  bool slow_horizontal = xy_speed_demand_low || (xy_speed_low && !pos_control->is_active_xy()) || (control_mode == ALT_HOLD && small_angle_request);
58 
59  bool descent_demanded = pos_control->is_active_z() && des_climb_rate_cms < 0.0f;
60  bool slow_descent_demanded = descent_demanded && des_climb_rate_cms >= -100.0f;
61  bool z_speed_low = fabsf(inertial_nav.get_velocity_z()) <= 60.0f;
62  bool slow_descent = (slow_descent_demanded || (z_speed_low && descent_demanded));
63 
64  gndeffect_state.touchdown_expected = slow_horizontal && slow_descent;
65 
66  // Prepare the EKF for ground effect if either takeoff or touchdown is expected.
67  ahrs.setTakeoffExpected(gndeffect_state.takeoff_expected);
68  ahrs.setTouchdownExpected(gndeffect_state.touchdown_expected);
69 }
struct Copter::@4 gndeffect_state
float get_velocity_z() const
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
float get_altitude() const
const Vector3f & get_vel_target() const
void setTakeoffExpected(bool val)
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
bool optflow_position_ok()
Definition: system.cpp:344
MOTOR_CLASS * motors
Definition: Copter.h:422
bool is_active_xy() const
const Vector3f & get_velocity() const
bool is_active_z() const
RC_Channel * channel_throttle
Definition: Copter.h:223
void update_ground_effect_detector(void)
int16_t get_control_in() const
Mode * flightmode
Definition: Copter.h:955
#define f(i)
uint32_t millis()
float length(void) const
const Vector3f & get_desired_velocity()
AP_Int8 gndeffect_comp_enabled
Definition: Parameters.h:522
AC_PosControl * pos_control
Definition: Copter.h:493
bool position_ok()
Definition: system.cpp:312
virtual bool has_manual_throttle() const =0
ParametersG2 g2
Definition: Copter.h:209
void setTouchdownExpected(bool val)
control_mode_t control_mode
Definition: Copter.h:345