Package edu.wpi.first.wpilibj
Class PIDController
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.PIDBase
-
- edu.wpi.first.wpilibj.PIDController
-
- All Implemented Interfaces:
Controller
,PIDInterface
,PIDOutput
,Sendable
,AutoCloseable
public class PIDController extends PIDBase implements Controller
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)
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)
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)
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)
Allocate a PID object with the given constants for P, I, D and period.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
close()
void
disable()
Stop running the PIDController, this sets the output to zero before stopping.void
enable()
Begin running the PIDController.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.boolean
isEnabled()
Return true if PIDController is enabled.void
reset()
Reset the previous error, the integral term, and disable the controller.void
setEnabled(boolean enable)
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, getSetpoint, onTarget, pidWrite, setAbsoluteTolerance, setContinuous, setContinuous, setD, setF, setI, setInputRange, setOutputRange, setP, setPercentTolerance, setPID, setPID, setSetpoint, setTolerance, setToleranceBuffer
-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
PIDController
public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output, double period)
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)
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)
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)
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()
- Specified by:
close
in interfaceAutoCloseable
- Overrides:
close
in classSendableBase
-
enable
public void enable()
Begin running the PIDController.- Specified by:
enable
in interfaceController
-
disable
public void disable()
Stop running the PIDController, this sets the output to zero before stopping.- Specified by:
disable
in interfaceController
-
setEnabled
public void setEnabled(boolean enable)
Set the enabled state of the PIDController.
-
isEnabled
public boolean isEnabled()
Return true if PIDController is enabled.
-
reset
public void reset()
Reset the previous error, the integral term, and disable the controller.- Specified by:
reset
in interfacePIDInterface
- Overrides:
reset
in classPIDBase
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Overrides:
initSendable
in classPIDBase
- Parameters:
builder
- sendable builder
-
-