mirror of https://github.com/ArduPilot/ardupilot
MotorsMatrix: fix div by zero by ensuring throttle is above min
This commit is contained in:
parent
86ef4a738c
commit
31a55b2bd6
|
@ -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…
Reference in New Issue