11 if (
motors->armed() &&
ap.land_complete && !
copter.flightmode->has_manual_throttle() &&
25 float target_roll, target_pitch;
26 float target_yaw_rate;
27 float pilot_throttle_scaled;
30 if (!
motors->armed() ||
ap.throttle_zero || !
motors->get_interlock()) {
55 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
void zero_throttle_and_relax_ac()
virtual void run() override
void update_simple_mode(void)
AC_AttitudeControl_t *& attitude_control
float get_pilot_desired_yaw_rate(int16_t stick_angle)
float get_non_takeoff_throttle(void)
int16_t get_control_in() const
virtual bool init(bool ignore_checks) override
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
void set_alt_target(float alt_cm)
AP_HAL_MAIN_CALLBACKS & copter
RC_Channel *& channel_yaw
void set_land_complete(bool b)
AP_Vehicle::MultiCopter aparm
RC_Channel *& channel_throttle