Browse Source

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

master
Leonard Hall 10 years ago committed by Randy Mackay
parent
commit
31a55b2bd6
  1. 2
      libraries/AP_Motors/AP_MotorsMatrix.cpp

2
libraries/AP_Motors/AP_MotorsMatrix.cpp

@ -185,6 +185,8 @@ void AP_MotorsMatrix::output_armed() @@ -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

Loading…
Cancel
Save