From 027284fba0489e0a6e35d9c7a47e7a85e71d8785 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 22 Jan 2016 11:09:18 +0900 Subject: [PATCH] AP_MotorsMatrix: roll, pitch, yaw input in -1 to +1 range --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 353b027293..e458c58080 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -176,9 +176,9 @@ void AP_MotorsMatrix::output_armed_stabilizing() float throttle_thrust_hover = get_hover_throttle_as_high_end_pct(); // throttle hover thrust value, 0.0 - 1.0 // 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