Browse Source

Copter: update Y6 defaults

master
Randy Mackay 12 years ago
parent
commit
81074ebb3c
  1. 13
      ArduCopter/config.h

13
ArduCopter/config.h

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

Loading…
Cancel
Save