MotorTri: check servo_out above min_throttle

This commit is contained in:
Randy Mackay 2015-03-16 13:42:34 +09:00
parent f9e29a7f77
commit 385b3744ea
1 changed files with 2 additions and 0 deletions

View File

@ -141,6 +141,8 @@ void AP_MotorsTri::output_armed()
// check if throttle is 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
}
//left front
motor_out[AP_MOTORS_MOT_2] = _rc_throttle.radio_out + roll_out + pitch_out;