From 91c3f993b42f451cb38737710c4c322b06f016e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 2 Mar 2012 17:24:44 +1100 Subject: [PATCH] ACM: set default RC fast speed to 400Hz --- ArduCopter/config.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 3583645efd..3435cec68c 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -105,6 +105,11 @@ # define INSTANT_PWM DISABLED #endif +// default RC speed in Hz if INSTANT_PWM is not used +#ifndef RC_FAST_SPEED +# define RC_FAST_SPEED 400 +#endif + // LED and IO Pins // #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1