36 ap.land_repo_active =
false;
58 if (!
motors->armed() || !
ap.auto_armed ||
ap.land_complete || !
motors->get_interlock()) {
63 if (
ap.land_complete) {
64 copter.init_disarm_motors();
86 float target_roll = 0.0f, target_pitch = 0.0f;
87 float target_yaw_rate = 0;
90 if (!
copter.failsafe.radio) {
110 if (!
motors->armed() || !
ap.auto_armed ||
ap.land_complete || !
motors->get_interlock()) {
111 #if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw 113 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
122 if (
ap.land_complete) {
123 copter.init_disarm_motors();
132 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
void zero_throttle_and_relax_ac()
bool set_mode(control_mode_t mode, mode_reason_t reason)
virtual float get_velocity_z() const=0
#define LAND_WITH_DELAY_MS
static bool land_with_gps
AP_Int16 throttle_behavior
uint32_t failsafe_mode_change
void Log_Write_Event(uint8_t id)
void update_simple_mode(void)
float get_accel_z() const
void set_mode_land_with_pause(mode_reason_t reason)
AC_AttitudeControl_t *& attitude_control
void init_target(const Vector3f &position)
float get_pilot_desired_yaw_rate(int16_t stick_angle)
float get_speed_down() const
AP_Int8 land_repositioning
void land_run_horizontal_control()
void land_run_vertical_control(bool pause_descent=false)
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND
void get_stopping_point_xy(Vector3f &stopping_point) const
int16_t get_control_in() const
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
float get_speed_up() const
static uint32_t land_start_time
void set_accel_z(float accel_cmss)
#define DATA_LAND_CANCELLED_BY_PILOT
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
AP_HAL_MAIN_CALLBACKS & copter
#define LAND_CANCEL_TRIGGER_THR
AP_InertialNav & inertial_nav
RC_Channel *& channel_yaw
static struct notify_events_type events
control_mode_t control_mode
bool init(bool ignore_checks) override
void set_alt_target_to_current_alt()