Package edu.wpi.first.math.controller
Class PIDController
java.lang.Object
edu.wpi.first.math.controller.PIDController
- All Implemented Interfaces:
Sendable,AutoCloseable
Implements a PID control loop.
-
Constructor Summary
ConstructorsConstructorDescriptionPIDController(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 TypeMethodDescriptionbooleanReturns true if the error is within the tolerance of the setpoint.doublecalculate(double measurement) Returns the next output of the PID controller.doublecalculate(double measurement, double setpoint) Returns the next output of the PID controller.voidclose()voidDisables continuous input.voidenableContinuousInput(double minimumInput, double maximumInput) Enables continuous input.doubleReturns the accumulated error used in the integral calculation of this controller.doublegetD()Get the Differential coefficient.doublegetError()Returns the difference between the setpoint and the measurement.doubleReturns the error derivative.doubleReturns the error derivative tolerance of this controller.doubleReturns the error tolerance of this controller.doublegetI()Get the Integral coefficient.doublegetIZone()Get the IZone range.doublegetP()Get the Proportional coefficient.doubleReturns the period of this controller.doubleDeprecated, for removal: This API element is subject to removal in a future version.Use getError() instead.doubleDeprecated, for removal: This API element is subject to removal in a future version.Use getErrorTolerance() instead.doubleReturns the current setpoint of the PIDController.doubleDeprecated, for removal: This API element is subject to removal in a future version.Use getErrorDerivative() instead.doubleDeprecated, for removal: This API element is subject to removal in a future version.Use getErrorDerivativeTolerance() instead.voidinitSendable(SendableBuilder builder) Initializes thisSendableobject.booleanReturns true if continuous input is enabled.voidreset()Resets the previous error and the integral term.voidsetD(double kd) Sets the Differential coefficient of the PID controller gain.voidsetI(double ki) Sets the Integral coefficient of the PID controller gain.voidsetIntegratorRange(double minimumIntegral, double maximumIntegral) Sets the minimum and maximum contributions of the integral term.voidsetIZone(double iZone) Sets the IZone range.voidsetP(double kp) Sets the Proportional coefficient of the PID controller gain.voidsetPID(double kp, double ki, double kd) Sets the PID Controller gain parameters.voidsetSetpoint(double setpoint) Sets the setpoint for the PIDController.voidsetTolerance(double errorTolerance) Sets the error which is considered tolerable for use with atSetpoint().voidsetTolerance(double errorTolerance, double errorDerivativeTolerance) 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.- Throws:
IllegalArgumentException- if kp < 0IllegalArgumentException- if ki < 0IllegalArgumentException- if kd < 0
-
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.- Throws:
IllegalArgumentException- if kp < 0IllegalArgumentException- if ki < 0IllegalArgumentException- if kd < 0IllegalArgumentException- if period <= 0
-
-
Method Details
-
close
- Specified by:
closein 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- The proportional coefficient. Must be >= 0.
-
setI
Sets the Integral coefficient of the PID controller gain.- Parameters:
ki- The integral coefficient. Must be >= 0.
-
setD
Sets the Differential coefficient of the PID controller gain.- Parameters:
kd- The differential coefficient. Must be >= 0.
-
setIZone
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 ofDouble.POSITIVE_INFINITYdisables IZone functionality.- Parameters:
iZone- Maximum magnitude of error to allow integral control.- Throws:
IllegalArgumentException- if iZone < 0
-
getP
Get the Proportional coefficient.- Returns:
- proportional coefficient
-
getI
Get the Integral coefficient.- Returns:
- integral coefficient
-
getD
Get the Differential coefficient.- Returns:
- differential coefficient
-
getIZone
Get the IZone range.- Returns:
- Maximum magnitude of error to allow integral control.
-
getPeriod
Returns the period of this controller.- Returns:
- the period of the controller.
-
getPositionTolerance
Deprecated, for removal: This API element is subject to removal in a future version.Use getErrorTolerance() instead.Returns the position tolerance of this controller.- Returns:
- the position tolerance of the controller.
-
getVelocityTolerance
Deprecated, for removal: This API element is subject to removal in a future version.Use getErrorDerivativeTolerance() instead.Returns the velocity tolerance of this controller.- Returns:
- the velocity tolerance of the controller.
-
getErrorTolerance
Returns the error tolerance of this controller. Defaults to 0.05.- Returns:
- the error tolerance of the controller.
-
getErrorDerivativeTolerance
Returns the error derivative tolerance of this controller. Defaults to ∞.- Returns:
- the error derivative tolerance of the controller.
-
getAccumulatedError
Returns the accumulated error used in the integral calculation of this controller.- Returns:
- The accumulated error of this 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. The error tolerance defaults to 0.05, and the error derivative tolerance defaults to ∞.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 contributions of the integral term.The internal integrator is clamped so that the integral term's contribution to the output stays between minimumIntegral and maximumIntegral. This prevents integral windup.
- Parameters:
minimumIntegral- The minimum contribution of the integral term.maximumIntegral- The maximum contribution of the integral term.
-
setTolerance
Sets the error which is considered tolerable for use with atSetpoint().- Parameters:
errorTolerance- Error which is tolerable.
-
setTolerance
Sets the error which is considered tolerable for use with atSetpoint().- Parameters:
errorTolerance- Error which is tolerable.errorDerivativeTolerance- Error derivative which is tolerable.
-
getPositionError
Deprecated, for removal: This API element is subject to removal in a future version.Use getError() instead.Returns the difference between the setpoint and the measurement.- Returns:
- The error.
-
getVelocityError
Deprecated, for removal: This API element is subject to removal in a future version.Use getErrorDerivative() instead.Returns the velocity error.- Returns:
- The velocity error.
-
getError
Returns the difference between the setpoint and the measurement.- Returns:
- The error.
-
getErrorDerivative
Returns the error derivative.- Returns:
- The error derivative.
-
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:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-