From b0c9a25024ee195092a7b0de816b14095add38fe Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Sat, 31 Mar 2012 09:28:25 +0900
Subject: [PATCH] ArduCopter - CH6 tuning - changed Roll/Pitch Rate D tuning to
 use the user supplied tuning range instead of the range / 100.             
 also changed heli_ext_gyro_gain to make it use the tuning range directly.

---
 ArduCopter/ArduCopter.pde | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 8f2784572..8a949023d 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -2024,7 +2024,6 @@ static void tuning(){
 			break;
 
 		case CH6_RATE_KD:
-			tuning_value = (float)g.rc_6.control_in / 100000.0;
 			g.pid_rate_roll.kD(tuning_value);
 			g.pid_rate_pitch.kD(tuning_value);
 			break;
@@ -2127,7 +2126,7 @@ static void tuning(){
 
 		#if FRAME_CONFIG == HELI_FRAME
 		case CH6_HELI_EXTERNAL_GYRO:
-			g.heli_ext_gyro_gain = tuning_value * 1000;
+			g.heli_ext_gyro_gain = tuning_value;
 			break;
 		#endif
 
-- 
GitLab