mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PID: return P and D as output with slew limit and sum limit applyed
This commit is contained in:
parent
5065770e30
commit
2d75b0312e
@ -323,7 +323,7 @@ void AC_PID::update_i(float dt, bool limit)
|
||||
|
||||
float AC_PID::get_p() const
|
||||
{
|
||||
return _error * _kp;
|
||||
return _pid_info.P;
|
||||
}
|
||||
|
||||
float AC_PID::get_i() const
|
||||
@ -333,7 +333,7 @@ float AC_PID::get_i() const
|
||||
|
||||
float AC_PID::get_d() const
|
||||
{
|
||||
return _kd * _derivative;
|
||||
return _pid_info.D;
|
||||
}
|
||||
|
||||
float AC_PID::get_ff() const
|
||||
|
Loading…
Reference in New Issue
Block a user