From 3fc3858fbd47fc4598d468f6211370ab2fb7b46c Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sun, 20 Dec 2015 17:39:08 +1030 Subject: [PATCH] AP_MotorsMulticopter: set_throttle_range calcs _min_throttle before use --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 3458623477..cea0c7a6ec 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -370,8 +370,8 @@ void AP_MotorsMulticopter::set_throttle_range(uint16_t min_throttle, int16_t rad _throttle_radio_min = radio_min; _throttle_radio_max = radio_max; _throttle_pwm_scalar = (_throttle_radio_max - _throttle_radio_min) / 1000.0f; + _min_throttle = (float)min_throttle * _throttle_pwm_scalar; _rpy_pwm_scalar = (_throttle_radio_max - (_throttle_radio_min + _min_throttle)) / 9000.0f; - _min_throttle = (float)min_throttle * _throttle_pwm_scalar; } void AP_MotorsMulticopter::output_logic()