Robot Core Documentation
Loading...
Searching...
No Matches
edu.wpi.first.math.controller.PIDController Class Reference
Inheritance diagram for edu.wpi.first.math.controller.PIDController:
edu.wpi.first.util.sendable.Sendable

Public Member Functions

 PIDController (double kp, double ki, double kd)
 
 PIDController (double kp, double ki, double kd, double period)
 
void setPID (double kp, double ki, double kd)
 
void setP (double kp)
 
void setI (double ki)
 
void setD (double kd)
 
void setIZone (double iZone)
 
double getP ()
 
double getI ()
 
double getD ()
 
double getIZone ()
 
double getPeriod ()
 
double getPositionTolerance ()
 
double getVelocityTolerance ()
 
void setSetpoint (double setpoint)
 
double getSetpoint ()
 
boolean atSetpoint ()
 
void enableContinuousInput (double minimumInput, double maximumInput)
 
void disableContinuousInput ()
 
boolean isContinuousInputEnabled ()
 
void setIntegratorRange (double minimumIntegral, double maximumIntegral)
 
void setTolerance (double positionTolerance)
 
void setTolerance (double positionTolerance, double velocityTolerance)
 
double getPositionError ()
 
double getVelocityError ()
 
double calculate (double measurement, double setpoint)
 
double calculate (double measurement)
 
void reset ()
 
void initSendable (SendableBuilder builder)
 
- Public Member Functions inherited from edu.wpi.first.util.sendable.Sendable

Detailed Description

Implements a PID control loop.

Constructor & Destructor Documentation

◆ PIDController() [1/2]

edu.wpi.first.math.controller.PIDController.PIDController ( double kp,
double ki,
double kd )

Allocates a PIDController with the given constants for kp, ki, and kd and a default period of 0.02 seconds.

Parameters
kpThe proportional coefficient.
kiThe integral coefficient.
kdThe derivative coefficient.
Exceptions
IllegalArgumentExceptionif kp < 0
IllegalArgumentExceptionif ki < 0
IllegalArgumentExceptionif kd < 0

◆ PIDController() [2/2]

edu.wpi.first.math.controller.PIDController.PIDController ( double kp,
double ki,
double kd,
double period )

Allocates a PIDController with the given constants for kp, ki, and kd.

Parameters
kpThe proportional coefficient.
kiThe integral coefficient.
kdThe derivative coefficient.
periodThe period between controller updates in seconds.
Exceptions
IllegalArgumentExceptionif kp < 0
IllegalArgumentExceptionif ki < 0
IllegalArgumentExceptionif kd < 0
IllegalArgumentExceptionif period <= 0

Member Function Documentation

◆ atSetpoint()

boolean edu.wpi.first.math.controller.PIDController.atSetpoint ( )

Returns true if the error is within the tolerance of the setpoint.

This will return false until at least one input value has been computed.

Returns
Whether the error is within the acceptable bounds.

◆ calculate() [1/2]

double edu.wpi.first.math.controller.PIDController.calculate ( double measurement)

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
Returns
The next controller output.

◆ calculate() [2/2]

double edu.wpi.first.math.controller.PIDController.calculate ( double measurement,
double setpoint )

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
setpointThe new setpoint of the controller.
Returns
The next controller output.

◆ disableContinuousInput()

void edu.wpi.first.math.controller.PIDController.disableContinuousInput ( )

Disables continuous input.

◆ enableContinuousInput()

void edu.wpi.first.math.controller.PIDController.enableContinuousInput ( double minimumInput,
double maximumInput )

Enables continuous input.

Rather then using the max and min input range as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.

Parameters
minimumInputThe minimum value expected from the input.
maximumInputThe maximum value expected from the input.

◆ getD()

double edu.wpi.first.math.controller.PIDController.getD ( )

Get the Differential coefficient.

Returns
differential coefficient

◆ getI()

double edu.wpi.first.math.controller.PIDController.getI ( )

Get the Integral coefficient.

Returns
integral coefficient

◆ getIZone()

double edu.wpi.first.math.controller.PIDController.getIZone ( )

Get the IZone range.

Returns
Maximum magnitude of error to allow integral control.

◆ getP()

double edu.wpi.first.math.controller.PIDController.getP ( )

Get the Proportional coefficient.

Returns
proportional coefficient

◆ getPeriod()

double edu.wpi.first.math.controller.PIDController.getPeriod ( )

Returns the period of this controller.

Returns
the period of the controller.

◆ getPositionError()

double edu.wpi.first.math.controller.PIDController.getPositionError ( )

Returns the difference between the setpoint and the measurement.

Returns
The error.

◆ getPositionTolerance()

double edu.wpi.first.math.controller.PIDController.getPositionTolerance ( )

Returns the position tolerance of this controller.

Returns
the position tolerance of the controller.

◆ getSetpoint()

double edu.wpi.first.math.controller.PIDController.getSetpoint ( )

Returns the current setpoint of the PIDController.

Returns
The current setpoint.

◆ getVelocityError()

double edu.wpi.first.math.controller.PIDController.getVelocityError ( )

Returns the velocity error.

Returns
The velocity error.

◆ getVelocityTolerance()

double edu.wpi.first.math.controller.PIDController.getVelocityTolerance ( )

Returns the velocity tolerance of this controller.

Returns
the velocity tolerance of the controller.

◆ initSendable()

void edu.wpi.first.math.controller.PIDController.initSendable ( SendableBuilder builder)

Initializes this Sendable object.

Parameters
buildersendable builder

Implements edu.wpi.first.util.sendable.Sendable.

◆ isContinuousInputEnabled()

boolean edu.wpi.first.math.controller.PIDController.isContinuousInputEnabled ( )

Returns true if continuous input is enabled.

Returns
True if continuous input is enabled.

◆ reset()

void edu.wpi.first.math.controller.PIDController.reset ( )

Resets the previous error and the integral term.

◆ setD()

void edu.wpi.first.math.controller.PIDController.setD ( double kd)

Sets the Differential coefficient of the PID controller gain.

Parameters
kdThe differential coefficient. Must be >= 0.

◆ setI()

void edu.wpi.first.math.controller.PIDController.setI ( double ki)

Sets the Integral coefficient of the PID controller gain.

Parameters
kiThe integral coefficient. Must be >= 0.

◆ setIntegratorRange()

void edu.wpi.first.math.controller.PIDController.setIntegratorRange ( double minimumIntegral,
double maximumIntegral )

Sets the minimum and maximum values for the integrator.

When the cap is reached, the integrator value is added to the controller output rather than the integrator value times the integral gain.

Parameters
minimumIntegralThe minimum value of the integrator.
maximumIntegralThe maximum value of the integrator.

◆ setIZone()

void edu.wpi.first.math.controller.PIDController.setIZone ( double iZone)

Sets the IZone range. When the absolute value of the position error is greater than IZone, the total accumulated error will reset to zero, disabling integral gain until the absolute value of the position error is less than IZone. This is used to prevent integral windup. Must be non-negative. Passing a value of zero will effectively disable integral gain. Passing a value of Double#POSITIVE_INFINITY disables IZone functionality.

Parameters
iZoneMaximum magnitude of error to allow integral control.
Exceptions
IllegalArgumentExceptionif iZone < 0

◆ setP()

void edu.wpi.first.math.controller.PIDController.setP ( double kp)

Sets the Proportional coefficient of the PID controller gain.

Parameters
kpThe proportional coefficient. Must be >= 0.

◆ setPID()

void edu.wpi.first.math.controller.PIDController.setPID ( double kp,
double ki,
double kd )

Sets the PID Controller gain parameters.

Set the proportional, integral, and differential coefficients.

Parameters
kpThe proportional coefficient.
kiThe integral coefficient.
kdThe derivative coefficient.

◆ setSetpoint()

void edu.wpi.first.math.controller.PIDController.setSetpoint ( double setpoint)

Sets the setpoint for the PIDController.

Parameters
setpointThe desired setpoint.

◆ setTolerance() [1/2]

void edu.wpi.first.math.controller.PIDController.setTolerance ( double positionTolerance)

Sets the error which is considered tolerable for use with atSetpoint().

Parameters
positionTolerancePosition error which is tolerable.

◆ setTolerance() [2/2]

void edu.wpi.first.math.controller.PIDController.setTolerance ( double positionTolerance,
double velocityTolerance )

Sets the error which is considered tolerable for use with atSetpoint().

Parameters
positionTolerancePosition error which is tolerable.
velocityToleranceVelocity error which is tolerable.

The documentation for this class was generated from the following file: