10 if (
copter.position_ok() || ignore_checks) {
27 #if PRECISION_LANDING == ENABLED 33 if (
ap.land_complete_maybe) {
40 if (!
copter.precland.target_acquired()) {
50 if (!
copter.precland.get_target_position_cm(target_pos)) {
54 if (!
copter.precland.get_target_velocity_relative_cms(target_vel_rel)) {
69 float target_roll, target_pitch;
70 float target_yaw_rate = 0.0f;
71 float target_climb_rate = 0.0f;
72 float takeoff_climb_rate = 0.0f;
79 if (!
copter.failsafe.radio) {
101 if (
ap.land_complete_maybe) {
110 }
else if (!
ap.auto_armed ||
ap.land_complete) {
117 switch (loiter_state) {
122 #if FRAME_CONFIG == HELI_FRAME 169 if (target_climb_rate < 0.0
f) {
187 #if PRECISION_LANDING == ENABLED 200 if (
copter.rangefinder_alt_ok()) {
virtual float get_velocity_z() const=0
float get_alt_target() const
bool takeoff_triggered(float target_climb_rate) const
virtual const Vector3f & get_position() const=0
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
float get_avoidance_adjusted_climbrate(float target_rate)
void update_z_controller()
uint16_t get_pilot_speed_dn(void)
void update_simple_mode(void)
void override_vehicle_velocity_xy(const Vector2f &vel_xy)
AC_AttitudeControl_t *& attitude_control
void init_target(const Vector3f &position)
float get_pilot_desired_climb_rate(float throttle_control)
float get_pilot_desired_yaw_rate(int16_t stick_angle)
void soften_for_landing()
bool _precision_loiter_enabled
AP_Float pilot_takeoff_alt
void set_xy_target(float x, float y)
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
void precision_loiter_xy()
bool init(bool ignore_checks) override
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
void takeoff_timer_start(float alt_cm)
int16_t get_control_in() const
int32_t get_bearing_to_target() const
void relax_alt_hold_controllers(float throttle_setting)
void set_desired_velocity_z(float vel_z_cms)
uint32_t wp_distance() const override
void set_speed_z(float speed_down, float speed_up)
void set_throttle_takeoff(void)
int32_t wp_bearing() const override
Vector2f get_pilot_desired_acceleration() const
void set_accel_z(float accel_cmss)
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
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
bool do_precision_loiter()
takeoff_state_t & takeoff_state
float constrain_float(const float amt, const float low, const float high)
void clear_pilot_desired_acceleration()
AP_HAL_MAIN_CALLBACKS & copter
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
float & ekfNavVelGainScaler
AP_InertialNav & inertial_nav
virtual const Vector3f & get_velocity() const=0
float get_distance_to_target() const
RC_Channel *& channel_yaw
int32_t get_pitch() const
void set_land_complete(bool b)
RC_Channel *& channel_throttle
void set_alt_target_to_current_alt()
float get_angle_max_cd() const