mirror of https://github.com/ArduPilot/ardupilot
Plane: Quadaplane: use land_at_climb_rate_cm only when landing
This commit is contained in:
parent
f24cb7c502
commit
1614400cae
|
@ -8,7 +8,7 @@ bool ModeQHover::_enter()
|
||||||
// set vertical speed and acceleration limits
|
// set vertical speed and acceleration limits
|
||||||
pos_control->set_max_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
|
pos_control->set_max_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
|
||||||
pos_control->set_correction_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
|
pos_control->set_correction_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
|
||||||
quadplane.set_climb_rate_cms(0, false);
|
quadplane.set_climb_rate_cms(0);
|
||||||
|
|
||||||
quadplane.init_throttle_wait();
|
quadplane.init_throttle_wait();
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -103,13 +103,13 @@ void ModeQLoiter::run()
|
||||||
quadplane.ahrs.set_touchdown_expected(true);
|
quadplane.ahrs.set_touchdown_expected(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
quadplane.set_climb_rate_cms(-descent_rate_cms, descent_rate_cms>0);
|
pos_control->land_at_climb_rate_cm(-descent_rate_cms, descent_rate_cms>0);
|
||||||
quadplane.check_land_complete();
|
quadplane.check_land_complete();
|
||||||
} else if (plane.control_mode == &plane.mode_guided && quadplane.guided_takeoff) {
|
} else if (plane.control_mode == &plane.mode_guided && quadplane.guided_takeoff) {
|
||||||
quadplane.set_climb_rate_cms(0, false);
|
quadplane.set_climb_rate_cms(0);
|
||||||
} else {
|
} else {
|
||||||
// update altitude target and call position controller
|
// update altitude target and call position controller
|
||||||
quadplane.set_climb_rate_cms(quadplane.get_pilot_desired_climb_rate_cms(), false);
|
quadplane.set_climb_rate_cms(quadplane.get_pilot_desired_climb_rate_cms());
|
||||||
}
|
}
|
||||||
quadplane.run_z_controller();
|
quadplane.run_z_controller();
|
||||||
}
|
}
|
||||||
|
|
|
@ -88,7 +88,7 @@ void ModeQRTL::run()
|
||||||
quadplane.get_weathervane_yaw_rate_cds());
|
quadplane.get_weathervane_yaw_rate_cds());
|
||||||
|
|
||||||
// climb at full WP nav speed
|
// climb at full WP nav speed
|
||||||
quadplane.set_climb_rate_cms(quadplane.wp_nav->get_default_speed_up(), false);
|
quadplane.set_climb_rate_cms(quadplane.wp_nav->get_default_speed_up());
|
||||||
quadplane.run_z_controller();
|
quadplane.run_z_controller();
|
||||||
|
|
||||||
ftype alt_diff;
|
ftype alt_diff;
|
||||||
|
|
|
@ -1003,9 +1003,9 @@ void QuadPlane::check_yaw_reset(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms, bool force_descend)
|
void QuadPlane::set_climb_rate_cms(float target_climb_rate_cms)
|
||||||
{
|
{
|
||||||
pos_control->land_at_climb_rate_cm(target_climb_rate_cms, force_descend);
|
pos_control->input_vel_accel_z(target_climb_rate_cms, 0, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1023,7 +1023,7 @@ void QuadPlane::hold_hover(float target_climb_rate_cms)
|
||||||
multicopter_attitude_rate_update(get_desired_yaw_rate_cds(false));
|
multicopter_attitude_rate_update(get_desired_yaw_rate_cds(false));
|
||||||
|
|
||||||
// call position controller
|
// call position controller
|
||||||
set_climb_rate_cms(target_climb_rate_cms, false);
|
set_climb_rate_cms(target_climb_rate_cms);
|
||||||
|
|
||||||
run_z_controller();
|
run_z_controller();
|
||||||
}
|
}
|
||||||
|
@ -2790,7 +2790,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
float zero = 0;
|
float zero = 0;
|
||||||
pos_control->input_pos_vel_accel_z(target_z, zero, 0);
|
pos_control->input_pos_vel_accel_z(target_z, zero, 0);
|
||||||
} else {
|
} else {
|
||||||
set_climb_rate_cms(0, false);
|
set_climb_rate_cms(0);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -2804,7 +2804,7 @@ void QuadPlane::vtol_position_controller(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
const float descent_rate_cms = landing_descent_rate_cms(height_above_ground);
|
const float descent_rate_cms = landing_descent_rate_cms(height_above_ground);
|
||||||
set_climb_rate_cms(-descent_rate_cms, descent_rate_cms>0);
|
pos_control->land_at_climb_rate_cm(-descent_rate_cms, descent_rate_cms>0);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2952,10 +2952,10 @@ void QuadPlane::takeoff_controller(void)
|
||||||
vel_z = 0;
|
vel_z = 0;
|
||||||
pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0);
|
pos_control->input_pos_vel_accel_z(pos_z, vel_z, 0);
|
||||||
} else {
|
} else {
|
||||||
set_climb_rate_cms(vel_z, false);
|
set_climb_rate_cms(vel_z);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
set_climb_rate_cms(vel_z, false);
|
set_climb_rate_cms(vel_z);
|
||||||
}
|
}
|
||||||
|
|
||||||
run_z_controller();
|
run_z_controller();
|
||||||
|
@ -3000,7 +3000,7 @@ void QuadPlane::waypoint_controller(void)
|
||||||
true);
|
true);
|
||||||
|
|
||||||
// climb based on altitude error
|
// climb based on altitude error
|
||||||
set_climb_rate_cms(assist_climb_rate_cms(), false);
|
set_climb_rate_cms(assist_climb_rate_cms());
|
||||||
run_z_controller();
|
run_z_controller();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -225,7 +225,7 @@ private:
|
||||||
void hold_stabilize(float throttle_in);
|
void hold_stabilize(float throttle_in);
|
||||||
|
|
||||||
// set climb rate in position controller
|
// set climb rate in position controller
|
||||||
void set_climb_rate_cms(float target_climb_rate_cms, bool force_descend);
|
void set_climb_rate_cms(float target_climb_rate_cms);
|
||||||
|
|
||||||
// get pilot desired yaw rate in cd/s
|
// get pilot desired yaw rate in cd/s
|
||||||
float get_pilot_input_yaw_rate_cds(void) const;
|
float get_pilot_input_yaw_rate_cds(void) const;
|
||||||
|
|
Loading…
Reference in New Issue