15 uint32_t tnow_ms =
millis();
16 float xy_des_speed_cms = 0.0f;
17 float xy_speed_cms = 0.0f;
23 xy_des_speed_cms = vel_target.
length();
29 xy_speed_cms = vel.
length();
41 if (!throttle_up &&
ap.land_complete) {
54 bool small_angle_request = cosf(angle_target_rad.
x)*cosf(angle_target_rad.
y) > cosf(radians(7.5
f));
60 bool slow_descent_demanded = descent_demanded && des_climb_rate_cms >= -100.0f;
62 bool slow_descent = (slow_descent_demanded || (z_speed_low && descent_demanded));
struct Copter::@4 gndeffect_state
float get_velocity_z() const
AC_AttitudeControl_t * attitude_control
float get_altitude() const
const Vector3f & get_vel_target() const
void setTakeoffExpected(bool val)
AP_InertialNav_NavEKF inertial_nav
bool optflow_position_ok()
bool is_active_xy() const
const Vector3f & get_velocity() const
RC_Channel * channel_throttle
void update_ground_effect_detector(void)
int16_t get_control_in() const
const Vector3f & get_desired_velocity()
AP_Int8 gndeffect_comp_enabled
AC_PosControl * pos_control
virtual bool has_manual_throttle() const =0
void setTouchdownExpected(bool val)
control_mode_t control_mode