3 #if MODE_CIRCLE_ENABLED == ENABLED 12 if (
copter.position_ok() || ignore_checks) {
34 float target_yaw_rate = 0;
35 float target_climb_rate = 0;
44 if (!
motors->armed() || !
ap.auto_armed ||
ap.land_complete || !
motors->get_interlock()) {
52 if (!
copter.failsafe.radio) {
55 if (!
is_zero(target_yaw_rate)) {
63 if (
ap.land_complete && target_climb_rate > 0) {
75 copter.circle_nav->update();
80 copter.circle_nav->get_pitch(),
84 copter.circle_nav->get_pitch(),
85 copter.circle_nav->get_yaw(),
true);
89 if (
copter.rangefinder_alt_ok()) {
100 return copter.circle_nav->get_distance_to_target();
105 return copter.circle_nav->get_bearing_to_target();
void zero_throttle_and_relax_ac()
float get_alt_target() const
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
bool init(bool ignore_checks) override
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
void update_z_controller()
uint16_t get_pilot_speed_dn(void)
AC_AttitudeControl_t *& attitude_control
float get_pilot_desired_climb_rate(float throttle_control)
uint32_t wp_distance() const override
float get_pilot_desired_yaw_rate(int16_t stick_angle)
float get_speed_xy() const
int16_t get_control_in() const
bool is_zero(const T fVal1)
void set_speed_z(float speed_down, float speed_up)
void set_throttle_takeoff(void)
void set_accel_z(float accel_cmss)
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
float get_wp_acceleration() const
void set_accel_xy(float accel_cmss)
AP_HAL_MAIN_CALLBACKS & copter
RC_Channel *& channel_yaw
int32_t wp_bearing() const override
void set_speed_xy(float speed_cms)
void set_land_complete(bool b)
RC_Channel *& channel_throttle
void set_alt_target_to_current_alt()