Sub: Change default pwm frequency to 200Hz

This commit is contained in:
Jacob Walser 2016-12-07 11:43:30 -05:00 committed by Andrew Tridgell
parent 2bb3286faa
commit b108620742
2 changed files with 3 additions and 3 deletions

View File

@ -588,7 +588,7 @@ const AP_Param::Info Sub::var_info[] = {
// @Range: 50 490
// @Increment: 1
// @User: Advanced
GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
GSCALAR(rc_speed, "RC_SPEED", RC_SPEED_DEFAULT),
// @Param: ACRO_RP_P
// @DisplayName: Acro Roll and Pitch P gain

View File

@ -82,8 +82,8 @@
//////////////////////////////////////////////////////////////////////////////
// PWM control
// default RC speed in Hz
#ifndef RC_FAST_SPEED
# define RC_FAST_SPEED 490
#ifndef RC_SPEED_DEFAULT
# define RC_SPEED_DEFAULT 200
#endif
//////////////////////////////////////////////////////////////////////////////