AP_MotorsSingle: roll, pitch, yaw input in -1 to +1 range

This commit is contained in:
Leonard Hall 2016-01-22 11:10:09 +09:00 committed by Randy Mackay
parent 1a308c2eb8
commit b701c109cf

View File

@ -202,9 +202,9 @@ void AP_MotorsSingle::output_armed_stabilizing()
float actuator_max = 0.0f; // maximum actuator value
// apply voltage and air pressure compensation
roll_thrust = get_roll_thrust() * get_compensation_gain();
pitch_thrust = get_pitch_thrust() * get_compensation_gain();
yaw_thrust = get_yaw_thrust() * get_compensation_gain();
roll_thrust = _roll_in * get_compensation_gain();
pitch_thrust = _pitch_in * get_compensation_gain();
yaw_thrust = _yaw_in * get_compensation_gain();
throttle_thrust = get_throttle() * get_compensation_gain();
// sanity check throttle is above zero and below current limited throttle