Copter: remove setting rate and thr D term filters

This commit is contained in:
Randy Mackay 2014-05-27 22:45:22 +09:00
parent 29ca7a10df
commit db000f2287
2 changed files with 0 additions and 13 deletions

View File

@ -561,10 +561,6 @@
// 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
@ -702,11 +698,6 @@
# define THROTTLE_ACCEL_IMAX 500
#endif
#ifndef THROTTLE_ACCEL_DTERM_FILTER
# define THROTTLE_ACCEL_DTERM_FILTER 20
#endif
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//

View File

@ -231,10 +231,6 @@ 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);
g.pid_throttle_accel.set_d_lpf_alpha(THROTTLE_ACCEL_DTERM_FILTER, MAIN_LOOP_SECONDS);
// init the optical flow sensor
if(g.optflow_enabled) {