mirror of https://github.com/ArduPilot/ardupilot
AC_PID: add slew_rate modifier
This commit is contained in:
parent
e3d7dd0776
commit
273ed18d34
|
@ -121,6 +121,12 @@ void AC_PID::filt_D_hz(float hz)
|
|||
_filt_D_hz.set(fabsf(hz));
|
||||
}
|
||||
|
||||
// slew_limit - set slew limit
|
||||
void AC_PID::slew_limit(float smax)
|
||||
{
|
||||
_slew_rate_max.set(fabsf(smax));
|
||||
}
|
||||
|
||||
// update_all - set target and measured inputs to PID controller and calculate outputs
|
||||
// target and error are filtered
|
||||
// the derivative is then calculated and filtered
|
||||
|
|
|
@ -101,6 +101,7 @@ public:
|
|||
void filt_T_hz(const float v);
|
||||
void filt_E_hz(const float v);
|
||||
void filt_D_hz(const float v);
|
||||
void slew_limit(const float v);
|
||||
|
||||
// set the desired and actual rates (for logging purposes)
|
||||
void set_target_rate(float target) { _pid_info.target = target; }
|
||||
|
|
Loading…
Reference in New Issue