diff --git a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp index 977bcd06a9..c9fec2e862 100644 --- a/libraries/AP_Motors/AP_MotorsMatrixTS.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrixTS.cpp @@ -76,7 +76,7 @@ void AP_MotorsMatrixTS::output_armed_stabilizing() // apply voltage and air pressure compensation const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain; - pitch_thrust = (_roll_in + _roll_in_ff) * compensation_gain; + pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain; throttle_thrust = get_throttle() * compensation_gain; // sanity check throttle is above zero and below current limited throttle