Browse Source

MotorSingle: check servo_out above min_throttle

We need to recalc radio_out or the motors could fall below min throttle
master
Randy Mackay 10 years ago
parent
commit
f9e29a7f77
  1. 2
      libraries/AP_Motors/AP_MotorsSingle.cpp

2
libraries/AP_Motors/AP_MotorsSingle.cpp

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

Loading…
Cancel
Save