Browse Source

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

master
rmackay9 13 years ago
parent
commit
090f5aaa6f
  1. 4
      ArduCopter/config.h

4
ArduCopter/config.h

@ -112,8 +112,12 @@ @@ -112,8 +112,12 @@
// default RC speed in Hz if INSTANT_PWM is not used
#ifndef RC_FAST_SPEED
# if FRAME_CONFIG == HELI_FRAME
# define RC_FAST_SPEED 125
# else
# define RC_FAST_SPEED 490
# endif
#endif
// LED and IO Pins
//

Loading…
Cancel
Save