diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 1e39b0abccbd5739ab610dd00d200d6eb35fe9f0..843d034beaf0a71e50a6f7bf36fcb9603ec5dc51 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -2043,10 +2043,6 @@ static void tuning(){
 
 	switch(g.radio_tuning){
 
-		case CH6_DAMP:
-			g.stabilize_d.set(tuning_value);
-			break;
-
 		case CH6_RATE_KD:
 			g.pid_rate_roll.kD(tuning_value);
 			g.pid_rate_pitch.kD(tuning_value);
@@ -2062,6 +2058,7 @@ static void tuning(){
 			g.pi_stabilize_pitch.kI(tuning_value);
 			break;
 
+		case CH6_DAMP:
 		case CH6_STABILIZE_KD:
 			g.stabilize_d = tuning_value;
 			break;
diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h
index 693f42987072166a8600b090062c4c0218425780..b0a5de2a5576e2b22a6e9dd7543540b0664410ba 100644
--- a/ArduCopter/defines.h
+++ b/ArduCopter/defines.h
@@ -145,7 +145,7 @@
 // Attitude
 #define CH6_STABILIZE_KP 1
 #define CH6_STABILIZE_KI 2
-#define CH6_STABILIZE_KD 29
+#define CH6_STABILIZE_KD 29		// duplicate with CH6_DAMP
 #define CH6_YAW_KP 3
 #define CH6_YAW_KI 24
 // Rate
@@ -172,7 +172,7 @@
 // altitude controller
 #define CH6_THR_HOLD_KP 14
 #define CH6_Z_GAIN 15
-#define CH6_DAMP 16
+#define CH6_DAMP 16		// duplicate with CH6_YAW_RATE_KD
 
 // optical flow controller
 #define CH6_OPTFLOW_KP 17