diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 607e4766af..9d3edad354 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -139,6 +139,12 @@ # define RATE_YAW_I 0.015f #endif +///////////////////////////////////////////////////////////////////////////////// +// Tri defaults +#if FRAME_CONFIG == TRI_FRAME + # define RATE_YAW_FILT_HZ 100.0f +#endif + ////////////////////////////////////////////////////////////////////////////// // PWM control // default RC speed in Hz