AP_MotorsCoax: fix stability patch use of throttle_hover

This commit is contained in:
Leonard Hall 2016-05-31 16:08:25 +09:00 committed by Randy Mackay
parent 9bc866e771
commit da05902805

View File

@ -238,7 +238,7 @@ void AP_MotorsCoax::output_armed_stabilizing()
_thrust_yt_cw = thrust_out - 0.5f * yaw_thrust;
// limit thrust out for calculation of actuator gains
float thrust_out_actuator = MAX(throttle_thrust_hover*0.5,thrust_out);
float thrust_out_actuator = MAX(_throttle_hover*0.5f,thrust_out);
if (is_zero(thrust_out_actuator)) {
limit.roll_pitch = true;