From 3b5ffe0f615e55e8b9b3f1eea75f76be48f4f796 Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Sat, 21 Apr 2012 23:46:36 +0900
Subject: [PATCH] ArduCopter - config.h - set standard RC_SPEED to 125 for
 helicopter frame

---
 ArduCopter/config.h | 6 +++++-
 1 file changed, 5 insertions(+), 1 deletion(-)

diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index cd961e264..ee91206b0 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -112,7 +112,11 @@
 
 // default RC speed in Hz if INSTANT_PWM is not used
 #ifndef RC_FAST_SPEED
-# define RC_FAST_SPEED 490
+# if FRAME_CONFIG == HELI_FRAME
+#   define RC_FAST_SPEED 125
+# else
+#   define RC_FAST_SPEED 490
+# endif
 #endif
 
 // LED and IO Pins
-- 
GitLab