Browse Source

Copter: Set Rate PID D-term filter rates on initialization.

mission-4.1.18
Robert Lefebvre 11 years ago committed by Randy Mackay
parent
commit
df1de4260d
  1. 5
      ArduCopter/config.h
  2. 3
      ArduCopter/system.pde

5
ArduCopter/config.h

@ -560,6 +560,11 @@ @@ -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

3
ArduCopter/system.pde

@ -231,6 +231,9 @@ static void init_ardupilot() @@ -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) {

Loading…
Cancel
Save