MotorCoax: check servo_out above min_throttle

We need to recalc radio_out or the motors could fall below min throttle
This commit is contained in:
Randy Mackay 2015-03-16 13:41:48 +09:00
parent b10730f35c
commit 8de5d16f96

View File

@ -159,6 +159,8 @@ void AP_MotorsCoax::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
}
// motors