diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 5e7d45002c..5e206a8f90 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -103,27 +103,27 @@ ///////////////////////////////////////////////////////////////////////////////// // TradHeli defaults #if FRAME_CONFIG == HELI_FRAME - # define RC_FAST_SPEED 125 + # define RC_FAST_SPEED 125 # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AHEAD - # define RATE_INTEGRATOR_LEAK_RATE 0.02f - # define RATE_ROLL_D 0 - # define RATE_PITCH_D 0 - # define HELI_PITCH_FF 0 - # define HELI_ROLL_FF 0 - # define HELI_YAW_FF 0 - # define STABILIZE_THROTTLE THROTTLE_MANUAL + # define RATE_INTEGRATOR_LEAK_RATE 0.02f + # define RATE_ROLL_D 0 + # define RATE_PITCH_D 0 + # define HELI_PITCH_FF 0 + # define HELI_ROLL_FF 0 + # define HELI_YAW_FF 0 + # define STABILIZE_THROTTLE THROTTLE_MANUAL # define MPU6K_FILTER 10 #endif ///////////////////////////////////////////////////////////////////////////////// // Y6 defaults #if FRAME_CONFIG == Y6_FRAME - # define RATE_ROLL_P 0.1f - # define RATE_ROLL_D 0.006f - # define RATE_PITCH_P 0.1f - # define RATE_PITCH_D 0.006f - # define RATE_YAW_P 0.150f - # define RATE_YAW_I 0.015f + # define RATE_ROLL_P 0.1f + # define RATE_ROLL_D 0.006f + # define RATE_PITCH_P 0.1f + # define RATE_PITCH_D 0.006f + # define RATE_YAW_P 0.150f + # define RATE_YAW_I 0.015f #endif