ArduCopter - config.h - set standard RC_SPEED to 125 for helicopter frame

This commit is contained in:
rmackay9 2012-04-21 23:46:36 +09:00
parent c993049c48
commit 090f5aaa6f

View File

@ -112,7 +112,11 @@
// default RC speed in Hz if INSTANT_PWM is not used // default RC speed in Hz if INSTANT_PWM is not used
#ifndef RC_FAST_SPEED #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 #endif
// LED and IO Pins // LED and IO Pins