AP_MotorsSingle: fix stability patch use of throttle_hover

This commit is contained in:
Leonard Hall 2016-05-31 16:08:36 +09:00 committed by Randy Mackay
parent e0f9fc8e40
commit 8fff32bde3

View File

@ -274,7 +274,7 @@ void AP_MotorsSingle::output_armed_stabilizing()
} }
// limit thrust out for calculation of actuator gains // 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.5,_thrust_out);
// force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared // force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared
// static thrust is proportional to the airflow velocity squared // static thrust is proportional to the airflow velocity squared