From ac764642ca7e3370285f7a13db3c236d613f2c51 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 31 Jan 2013 23:21:18 +0900
Subject: [PATCH] Copter: manual throttle scaling fix

Scaling of bottom half of throttle was changed from THR_MIN ~ 500.
Previously it was from 0 ~ 500.
---
 ArduCopter/Attitude.pde | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index eb39a3b28..02fd3ab0b 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -854,7 +854,7 @@ static int16_t get_pilot_desired_throttle(int16_t throttle_control)
     // check throttle is above, below or in the deadband
     if (throttle_control < THROTTLE_IN_MIDDLE) {
         // below the deadband
-        throttle_out = (float)throttle_control * (float)g.throttle_mid / 500.0f;
+        throttle_out = g.throttle_min + ((float)(throttle_control-g.throttle_min))*((float)(g.throttle_mid - g.throttle_min))/((float)(500-g.throttle_min));
     }else if(throttle_control > THROTTLE_IN_MIDDLE) {
         // above the deadband
         throttle_out = g.throttle_mid + ((float)(throttle_control-500))*(float)(1000-g.throttle_mid)/500.0f;
-- 
GitLab