Package edu.wpi.first.wpilibj
Class PIDController
- java.lang.Object
-
- edu.wpi.first.wpilibj.PIDBase
-
- edu.wpi.first.wpilibj.PIDController
-
- All Implemented Interfaces:
Controller,PIDInterface,PIDOutput,Sendable,AutoCloseable
@Deprecated(since="2020", forRemoval=true) public class PIDController extends PIDBase implements Controller, AutoCloseable
Deprecated, for removal: This API element is subject to removal in a future version.UsePIDControllerinstead.Class implements a PID Control Loop.Creates a separate thread which reads the given PIDSource and takes care of the integral calculations, as well as writing the given PIDOutput.
This feedback controller runs in discrete time, so time deltas are not used in the integral and derivative calculations. Therefore, the sample rate affects the controller's behavior for a given set of PID constants.
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj.PIDBase
PIDBase.AbsoluteTolerance, PIDBase.NullTolerance, PIDBase.PercentageTolerance, PIDBase.Tolerance
-
-
Field Summary
-
Fields inherited from class edu.wpi.first.wpilibj.PIDBase
kDefaultPeriod, m_enabled, m_pidInput, m_pidOutput, m_pidWriteMutex, m_setpointTimer, m_thisMutex
-
-
Constructor Summary
Constructors Constructor Description PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, using a 50ms period.PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output, double period)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, and F.PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, using a 50ms period.PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D and period.
-
Method Summary
All Methods Instance Methods Concrete Methods Deprecated Methods Modifier and Type Method Description voidclose()Deprecated, for removal: This API element is subject to removal in a future version.voiddisable()Deprecated, for removal: This API element is subject to removal in a future version.Stop running the PIDController, this sets the output to zero before stopping.voidenable()Deprecated, for removal: This API element is subject to removal in a future version.Begin running the PIDController.voidinitSendable(SendableBuilder builder)Deprecated, for removal: This API element is subject to removal in a future version.Initializes thisSendableobject.booleanisEnabled()Deprecated, for removal: This API element is subject to removal in a future version.Return true if PIDController is enabled.voidreset()Deprecated, for removal: This API element is subject to removal in a future version.Reset the previous error, the integral term, and disable the controller.voidsetEnabled(boolean enable)Deprecated, for removal: This API element is subject to removal in a future version.Set the enabled state of the PIDController.-
Methods inherited from class edu.wpi.first.wpilibj.PIDBase
calculate, calculateFeedForward, get, getAvgError, getContinuousError, getD, getDeltaSetpoint, getError, getF, getI, getP, getPIDSourceType, getSetpoint, onTarget, pidWrite, setAbsoluteTolerance, setContinuous, setContinuous, setD, setF, setI, setInputRange, setOutputRange, setP, setPercentTolerance, setPID, setPID, setPIDSourceType, setSetpoint, setTolerance, setToleranceBuffer
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
addChild, getName, getSubsystem, setName, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
PIDController
public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output, double period)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, and F.- Parameters:
Kp- the proportional coefficientKi- the integral coefficientKd- the derivative coefficientKf- the feed forward termsource- The PIDSource object that is used to get valuesoutput- The PIDOutput object that is set to the output percentageperiod- the loop time for doing calculations in seconds. This particularly affects calculations of the integral and differential terms. The default is 0.05 (50ms).
-
PIDController
public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D and period.- Parameters:
Kp- the proportional coefficientKi- the integral coefficientKd- the derivative coefficientsource- the PIDSource object that is used to get valuesoutput- the PIDOutput object that is set to the output percentageperiod- the loop time for doing calculations in seconds. This particularly affects calculations of the integral and differential terms. The default is 0.05 (50ms).
-
PIDController
public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, using a 50ms period.- Parameters:
Kp- the proportional coefficientKi- the integral coefficientKd- the derivative coefficientsource- The PIDSource object that is used to get valuesoutput- The PIDOutput object that is set to the output percentage
-
PIDController
public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output)Deprecated, for removal: This API element is subject to removal in a future version.Allocate a PID object with the given constants for P, I, D, using a 50ms period.- Parameters:
Kp- the proportional coefficientKi- the integral coefficientKd- the derivative coefficientKf- the feed forward termsource- The PIDSource object that is used to get valuesoutput- The PIDOutput object that is set to the output percentage
-
-
Method Detail
-
close
public void close()
Deprecated, for removal: This API element is subject to removal in a future version.- Specified by:
closein interfaceAutoCloseable- Overrides:
closein classPIDBase
-
enable
public void enable()
Deprecated, for removal: This API element is subject to removal in a future version.Begin running the PIDController.- Specified by:
enablein interfaceController
-
disable
public void disable()
Deprecated, for removal: This API element is subject to removal in a future version.Stop running the PIDController, this sets the output to zero before stopping.- Specified by:
disablein interfaceController
-
setEnabled
public void setEnabled(boolean enable)
Deprecated, for removal: This API element is subject to removal in a future version.Set the enabled state of the PIDController.
-
isEnabled
public boolean isEnabled()
Deprecated, for removal: This API element is subject to removal in a future version.Return true if PIDController is enabled.
-
reset
public void reset()
Deprecated, for removal: This API element is subject to removal in a future version.Reset the previous error, the integral term, and disable the controller.- Specified by:
resetin interfacePIDInterface- Overrides:
resetin classPIDBase
-
initSendable
public void initSendable(SendableBuilder builder)
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Overrides:
initSendablein classPIDBase- Parameters:
builder- sendable builder
-
-