Copter: autotune - fix call to relax_alt_hold_controllers

This commit is contained in:
Leonard Hall 2016-07-12 21:45:46 +09:00 committed by Randy Mackay
parent 205bac91a1
commit 5b277f4fb5
1 changed files with 2 additions and 2 deletions

View File

@ -271,7 +271,7 @@ void Copter::autotune_run()
if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-motors.get_throttle_hover());
pos_control.relax_alt_hold_controllers(0.0f);
return;
}
@ -304,7 +304,7 @@ void Copter::autotune_run()
}
// 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);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->get_control_in())-motors.get_throttle_hover());
pos_control.relax_alt_hold_controllers(0.0f);
}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) {