From f9e29a7f7785f819e644696417208635d3a359a2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 16 Mar 2015 13:42:11 +0900 Subject: [PATCH] MotorSingle: check servo_out above min_throttle We need to recalc radio_out or the motors could fall below min throttle --- libraries/AP_Motors/AP_MotorsSingle.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 850a49a08a..4646c8cafa 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -172,6 +172,8 @@ void AP_MotorsSingle::output_armed() // check if throttle is at or below limit if (_rc_throttle.servo_out <= _min_throttle) { limit.throttle_lower = true; + _rc_throttle.servo_out = _min_throttle; + _rc_throttle.calc_pwm(); // recalculate radio.out } //motor