diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 13b98fb594..34cba7f962 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -560,6 +560,11 @@ ////////////////////////////////////////////////////////////////////////////// // Rate controller gains // + +#ifndef RATE_PID_DTERM_FILTER + # define RATE_PID_DTERM_FILTER 20 // D-term filter rate cutoff frequency. Used for Roll, Pitch and Yaw Rate PID controllers. +#endif + #ifndef RATE_ROLL_P # define RATE_ROLL_P 0.150f #endif diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index c5788dab9b..38608aeaf4 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -231,6 +231,9 @@ static void init_ardupilot() // initialise attitude and position controllers attitude_control.set_dt(MAIN_LOOP_SECONDS); pos_control.set_dt(MAIN_LOOP_SECONDS); + g.pid_rate_roll.set_d_lpf_alpha(RATE_PID_DTERM_FILTER, MAIN_LOOP_SECONDS); + g.pid_rate_pitch.set_d_lpf_alpha(RATE_PID_DTERM_FILTER, MAIN_LOOP_SECONDS); + g.pid_rate_yaw.set_d_lpf_alpha(RATE_PID_DTERM_FILTER, MAIN_LOOP_SECONDS); // init the optical flow sensor if(g.optflow_enabled) {