public class PIDController extends PIDBase implements Controller
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.
PIDBase.AbsoluteTolerance, PIDBase.NullTolerance, PIDBase.PercentageTolerance, PIDBase.Tolerance
kDefaultPeriod, m_enabled, m_pidInput, m_pidOutput, m_pidWriteMutex, m_setpointTimer, m_thisMutex
Constructor and 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.
|
Modifier and Type | Method and 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 this
Sendable 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.
|
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
addChild, free, getName, getSubsystem, setName, setName, setName, setSubsystem
public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output, double period)
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).public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period)
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).public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output)
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 percentagepublic PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output)
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 percentagepublic void close()
close
in interface AutoCloseable
close
in class SendableBase
public void enable()
enable
in interface Controller
public void disable()
disable
in interface Controller
public void setEnabled(boolean enable)
public boolean isEnabled()
public void reset()
reset
in interface PIDInterface
reset
in class PIDBase
public void initSendable(SendableBuilder builder)
Sendable
Sendable
object.initSendable
in interface Sendable
initSendable
in class PIDBase
builder
- sendable builder