AC_PID: Fix before squash

This commit is contained in:
Leonard Hall 2021-05-19 23:40:14 +09:30 committed by Andrew Tridgell
parent 53439b19cd
commit 9e9e139f99
4 changed files with 6 additions and 5 deletions

View File

@ -72,7 +72,7 @@ AC_PID_2D::AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float
// 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
// the integral is then updated based on the setting of the limit flag
// the integral is then updated if it does not increase in the direction of the limit vector
Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measurement, const Vector2f &limit)
{
// don't process inf or NaN
@ -128,7 +128,7 @@ Vector2f AC_PID_2D::update_all(const Vector3f &target, const Vector3f &measureme
// update_i - update the integral
// If the limit is set the integral is only allowed to reduce in the direction of the limit
void AC_PID_2D::update_i( const Vector2f &limit)
void AC_PID_2D::update_i(const Vector2f &limit)
{
Vector2f limit_direction = limit;
Vector2f delta_integrator = (_error * _ki) * _dt;

View File

@ -23,7 +23,7 @@ public:
// 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
// the integral is then updated based on the setting of the limit flag
// the integral is then updated if it does not increase in the direction of the limit vector
Vector2f update_all(const Vector2f &target, const Vector2f &measurement, const Vector2f &limit);
Vector2f update_all(const Vector3f &target, const Vector3f &measurement, const Vector3f &limit);

View File

@ -74,7 +74,7 @@ void AC_P_1D::set_limits(float output_min, float output_max, float D_Out_max, fl
}
}
// set_error_limits - reduce maximum position error to error_max
// set_error_limits - reduce maximum error to error_max
// to be called after setting limits
void AC_P_1D::set_error_limits(float error_min, float error_max)
{

View File

@ -22,7 +22,8 @@ AC_P_2D::AC_P_2D(float initial_p, float dt) :
_kp = initial_p;
}
// set target and measured inputs to P controller and calculate outputs
// update_all - set target and measured inputs to P controller and calculate outputs
// limit is set true if the target has been moved to limit the maximum position error
Vector2f AC_P_2D::update_all(float &target_x, float &target_y, const Vector2f &measurement, bool &limit)
{
limit = false;