Browse Source

MotorCoax: check servo_out above min_throttle

We need to recalc radio_out or the motors could fall below min throttle
mission-4.1.18
Randy Mackay 10 years ago
parent
commit
8de5d16f96
  1. 2
      libraries/AP_Motors/AP_MotorsCoax.cpp

2
libraries/AP_Motors/AP_MotorsCoax.cpp

@ -159,6 +159,8 @@ void AP_MotorsCoax::output_armed() @@ -159,6 +159,8 @@ void AP_MotorsCoax::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
}
// motors

Loading…
Cancel
Save