From 090f5aaa6f7a2911b2c89f8b990a5b34a36e4df6 Mon Sep 17 00:00:00 2001 From: rmackay9 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 cd961e2642..ee91206b0e 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