MotorSingle: 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:42:11 +09:00
parent 8de5d16f96
commit f9e29a7f77

View File

@ -172,6 +172,8 @@ void AP_MotorsSingle::output_armed()
// check if throttle is at or below limit
if (_rc_throttle.servo_out <= _min_throttle) {
limit.throttle_lower = true;
_rc_throttle.servo_out = _min_throttle;
_rc_throttle.calc_pwm(); // recalculate radio.out
}
//motor