From b701c109cf90bd27ea6d6051cdbb49c93493dd72 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 22 Jan 2016 11:10:09 +0900 Subject: [PATCH] AP_MotorsSingle: roll, pitch, yaw input in -1 to +1 range --- libraries/AP_Motors/AP_MotorsSingle.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 1c79c87b8c..94432630ba 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -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