diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index d1f978271a..4fdf83e92f 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -185,6 +185,8 @@ void AP_MotorsMatrix::output_armed() // check if throttle is below limit if (_rc_throttle.servo_out <= _min_throttle) { // perhaps being at min throttle itself is not a problem, only being under is limit.throttle_lower = true; + _rc_throttle.servo_out = _min_throttle; + _rc_throttle.calc_pwm(); // recalculate radio.out } // calculate roll and pitch for each motor