Copter: update Y6 defaults

This commit is contained in:
Randy Mackay 2013-08-28 13:05:01 +09:00
parent 6052017b13
commit 81074ebb3c

View File

@ -104,7 +104,7 @@
#endif #endif
///////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////
// Bulk defines for TradHeli // TradHeli defaults
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME
# define RC_FAST_SPEED 125 # define RC_FAST_SPEED 125
# define WP_YAW_BEHAVIOR_DEFAULT YAW_LOOK_AT_HOME # define WP_YAW_BEHAVIOR_DEFAULT YAW_LOOK_AT_HOME
@ -118,6 +118,17 @@
# define MPU6K_FILTER 10 # define MPU6K_FILTER 10
#endif #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
#endif
// optical flow doesn't work in SITL yet // optical flow doesn't work in SITL yet
#ifdef DESKTOP_BUILD #ifdef DESKTOP_BUILD