From e7ba5ae451cdad30daac951f7d9d55b7d0ac61b5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 4 Feb 2016 17:11:00 +0900 Subject: [PATCH] AP_MotorsMulticopter: fix get_hover_throttle_as_high_end_pct --- 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 a77778b45b..bdd5d21f0f 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -272,7 +272,7 @@ void AP_MotorsMulticopter::update_throttle_rpy_mix() float AP_MotorsMulticopter::get_hover_throttle_as_high_end_pct() const { - return ((float)_hover_out / (1000.0f - _min_throttle)); + return (MAX(0,(float)_hover_out-_min_throttle) / (float)(1000-_min_throttle)); } float AP_MotorsMulticopter::get_compensation_gain() const