Copter: Add 'handle' to allow #define updating of AC_PID filter rate for Throttle Accel.
This commit is contained in:
parent
df1de4260d
commit
5eb206e6bb
@ -702,6 +702,10 @@
|
||||
# define THROTTLE_ACCEL_IMAX 500
|
||||
#endif
|
||||
|
||||
#ifndef THROTTLE_ACCEL_DTERM_FILTER
|
||||
# define THROTTLE_ACCEL_DTERM_FILTER 20
|
||||
#endif
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash logging control
|
||||
|
@ -234,6 +234,7 @@ static void init_ardupilot()
|
||||
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) {
|
||||
|
Loading…
Reference in New Issue
Block a user