MotorsMatrix: fix div by zero by ensuring throttle is above min

This commit is contained in:
Leonard Hall 2015-03-16 13:26:16 +09:00 committed by Randy Mackay
parent 86ef4a738c
commit 31a55b2bd6
1 changed files with 2 additions and 0 deletions

View File

@ -185,6 +185,8 @@ void AP_MotorsMatrix::output_armed()
// check if throttle is below limit // 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 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; limit.throttle_lower = true;
_rc_throttle.servo_out = _min_throttle;
_rc_throttle.calc_pwm(); // recalculate radio.out
} }
// calculate roll and pitch for each motor // calculate roll and pitch for each motor