Package edu.wpi.first.math.controller
Class PIDController
java.lang.Object
edu.wpi.first.math.controller.PIDController
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class PIDController extends Object implements Sendable, AutoCloseable
Implements a PID control loop.
-
Constructor Summary
Constructors Constructor Description 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.PIDController(double kp, double ki, double kd, double period)
Allocates a PIDController with the given constants for kp, ki, and kd. -
Method Summary
Modifier and Type Method Description boolean
atSetpoint()
Returns true if the error is within the tolerance of the setpoint.double
calculate(double measurement)
Returns the next output of the PID controller.double
calculate(double measurement, double setpoint)
Returns the next output of the PID controller.void
close()
void
disableContinuousInput()
Disables continuous input.void
enableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.double
getD()
Get the Differential coefficient.double
getI()
Get the Integral coefficient.double
getP()
Get the Proportional coefficient.double
getPeriod()
Returns the period of this controller.double
getPositionError()
Returns the difference between the setpoint and the measurement.double
getPositionTolerance()
Returns the position tolerance of this controller.double
getSetpoint()
Returns the current setpoint of the PIDController.double
getVelocityError()
Returns the velocity error.double
getVelocityTolerance()
Returns the velocity tolerance of this controller.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.boolean
isContinuousInputEnabled()
Returns true if continuous input is enabled.void
reset()
Resets the previous error and the integral term.void
setD(double kd)
Sets the Differential coefficient of the PID controller gain.void
setI(double ki)
Sets the Integral coefficient of the PID controller gain.void
setIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.void
setP(double kp)
Sets the Proportional coefficient of the PID controller gain.void
setPID(double kp, double ki, double kd)
Sets the PID Controller gain parameters.void
setSetpoint(double setpoint)
Sets the setpoint for the PIDController.void
setTolerance(double positionTolerance)
Sets the error which is considered tolerable for use with atSetpoint().void
setTolerance(double positionTolerance, double velocityTolerance)
Sets the error which is considered tolerable for use with atSetpoint().
-
Constructor Details
-
PIDController
Allocates a PIDController with the given constants for kp, ki, and kd and a default period of 0.02 seconds.- Parameters:
kp
- The proportional coefficient.ki
- The integral coefficient.kd
- The derivative coefficient.
-
PIDController
Allocates a PIDController with the given constants for kp, ki, and kd.- Parameters:
kp
- The proportional coefficient.ki
- The integral coefficient.kd
- The derivative coefficient.period
- The period between controller updates in seconds. Must be non-zero and positive.
-
-
Method Details
-
close
- Specified by:
close
in interfaceAutoCloseable
-
setPID
Sets the PID Controller gain parameters.Set the proportional, integral, and differential coefficients.
- Parameters:
kp
- The proportional coefficient.ki
- The integral coefficient.kd
- The derivative coefficient.
-
setP
Sets the Proportional coefficient of the PID controller gain.- Parameters:
kp
- proportional coefficient
-
setI
Sets the Integral coefficient of the PID controller gain.- Parameters:
ki
- integral coefficient
-
setD
Sets the Differential coefficient of the PID controller gain.- Parameters:
kd
- differential coefficient
-
getP
Get the Proportional coefficient.- Returns:
- proportional coefficient
-
getI
Get the Integral coefficient.- Returns:
- integral coefficient
-
getD
Get the Differential coefficient.- Returns:
- differential coefficient
-
getPeriod
Returns the period of this controller.- Returns:
- the period of the controller.
-
getPositionTolerance
Returns the position tolerance of this controller.- Returns:
- the position tolerance of the controller.
-
getVelocityTolerance
Returns the velocity tolerance of this controller.- Returns:
- the velocity tolerance of the controller.
-
setSetpoint
Sets the setpoint for the PIDController.- Parameters:
setpoint
- The desired setpoint.
-
getSetpoint
Returns the current setpoint of the PIDController.- Returns:
- The current setpoint.
-
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.
-
enableContinuousInput
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:
minimumInput
- The minimum value expected from the input.maximumInput
- The maximum value expected from the input.
-
disableContinuousInput
Disables continuous input. -
isContinuousInputEnabled
Returns true if continuous input is enabled.- Returns:
- True if continuous input is enabled.
-
setIntegratorRange
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:
minimumIntegral
- The minimum value of the integrator.maximumIntegral
- The maximum value of the integrator.
-
setTolerance
Sets the error which is considered tolerable for use with atSetpoint().- Parameters:
positionTolerance
- Position error which is tolerable.
-
setTolerance
Sets the error which is considered tolerable for use with atSetpoint().- Parameters:
positionTolerance
- Position error which is tolerable.velocityTolerance
- Velocity error which is tolerable.
-
getPositionError
Returns the difference between the setpoint and the measurement.- Returns:
- The error.
-
getVelocityError
Returns the velocity error.- Returns:
- The velocity error.
-
calculate
Returns the next output of the PID controller.- Parameters:
measurement
- The current measurement of the process variable.setpoint
- The new setpoint of the controller.- Returns:
- The next controller output.
-
calculate
Returns the next output of the PID controller.- Parameters:
measurement
- The current measurement of the process variable.- Returns:
- The next controller output.
-
reset
Resets the previous error and the integral term. -
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-