mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 18:23:57 -04:00
AC_PosControl: set Alt_Hold filter for PID not just D
We normally don't use the D term here so setting the filter for PID not just D lets us smooth the throttle response.
This commit is contained in:
parent
71b5584d17
commit
f4605b863c
@ -463,7 +463,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// set input to PID
|
// set input to PID
|
||||||
_pid_accel_z.set_input_filter_d(_accel_error.z);
|
_pid_accel_z.set_input_filter_all(_accel_error.z);
|
||||||
_pid_accel_z.set_desired_rate(accel_target_z);
|
_pid_accel_z.set_desired_rate(accel_target_z);
|
||||||
|
|
||||||
// separately calculate p, i, d values for logging
|
// separately calculate p, i, d values for logging
|
||||||
|
Loading…
Reference in New Issue
Block a user