10 if (
copter.position_ok() || ignore_checks) {
38 if (!
motors->armed() || !
ap.auto_armed || !
motors->get_interlock()) {
46 if (
ap.land_complete_maybe) {
51 if (
ap.land_complete) {
52 copter.init_disarm_motors();
void zero_throttle_and_relax_ac()
virtual float get_velocity_z() const=0
int32_t get_pitch() const
void update_z_controller()
void timeout_to_loiter_ms(uint32_t timeout_ms)
AC_AttitudeControl_t *& attitude_control
void soften_for_landing()
void init_brake_target(float accel_cmss)
void relax_alt_hold_controllers(float throttle_setting)
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
#define BRAKE_MODE_SPEED_Z
#define BRAKE_MODE_DECEL_RATE
void set_accel_z(float accel_cmss)
DESIRED_THROTTLE_UNLIMITED
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
AC_PosControl *& pos_control
AP_HAL_MAIN_CALLBACKS & copter
void update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler)
float & ekfNavVelGainScaler
AP_InertialNav & inertial_nav
bool init(bool ignore_checks) override
void set_alt_target_to_current_alt()