Copter: autotune provides throttle feedback from mid-stick when landed

This commit is contained in:
Randy Mackay 2016-08-01 11:12:16 +09:00
parent 88da5bd453
commit 6d9d3c1458

View File

@ -297,14 +297,17 @@ void Copter::autotune_run()
// reset target lean angles and heading while landed
if (ap.land_complete) {
if (ap.throttle_zero) {
// set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
if (target_climb_rate < 0.0f) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
}else{
} else {
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
}
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(channel_throttle->get_control_in()),false,g.throttle_filt);
attitude_control.reset_rate_controller_I_terms();
attitude_control.set_yaw_target_to_current_heading();
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
pos_control.relax_alt_hold_controllers(0.0f);
pos_control.update_z_controller();
}else{
// check if pilot is overriding the controls
if (!is_zero(target_roll) || !is_zero(target_pitch) || !is_zero(target_yaw_rate) || target_climb_rate != 0) {