public class PIDController extends java.lang.Object implements PIDInterface, LiveWindowSendable
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.
Modifier and Type | Class and Description |
---|---|
class |
PIDController.AbsoluteTolerance |
class |
PIDController.NullTolerance
Used internally for when Tolerance hasn't been set.
|
class |
PIDController.PercentageTolerance |
static interface |
PIDController.Tolerance
Tolerance is the type of tolerance used to specify if the PID controller is on target.
|
Modifier and Type | Field and Description |
---|---|
static double |
kDefaultPeriod |
protected PIDSource |
m_pidInput |
protected PIDOutput |
m_pidOutput |
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 |
---|---|
protected void |
calculate()
Read the input, calculate the output accordingly, and write to the output.
|
protected double |
calculateFeedForward()
Calculate the feed forward term.
|
void |
disable()
Stop running the PIDController, this sets the output to zero before stopping.
|
void |
enable()
Begin running the PIDController.
|
void |
free()
Free the PID object.
|
double |
get()
Return the current PID result This is always centered on zero and constrained the the max and
min outs.
|
double |
getAvgError()
Returns the current difference of the error over the past few iterations.
|
protected double |
getContinuousError(double error)
Wraps error around for continuous inputs.
|
double |
getD()
Get the Differential coefficient.
|
double |
getDeltaSetpoint()
Returns the change in setpoint over time of the PIDController.
|
double |
getError()
Returns the current difference of the input from the setpoint.
|
double |
getF()
Get the Feed forward coefficient.
|
double |
getI()
Get the Integral coefficient.
|
double |
getP()
Get the Proportional coefficient.
|
double |
getSetpoint()
Returns the current setpoint of the PIDController.
|
java.lang.String |
getSmartDashboardType()
The string representation of the named data type that will be used by the smart dashboard for
this
Sendable . |
ITable |
getTable()
The table that is associated with this
Sendable . |
void |
initTable(ITable table)
Initializes a table for this
Sendable object. |
boolean |
isEnable()
Deprecated.
Call
isEnabled() instead. |
boolean |
isEnabled()
Return true if PIDController is enabled.
|
boolean |
onTarget()
Return true if the error is within the percentage of the total input range, determined by
setTolerance.
|
void |
reset()
Reset the previous error,, the integral term, and disable the controller.
|
void |
setAbsoluteTolerance(double absvalue)
Set the absolute error which is considered tolerable for use with OnTarget.
|
void |
setContinuous()
Set the PID controller to consider the input to be continuous, Rather then using the max and
min in as constraints, it considers them to be the same point and automatically calculates the
shortest route to the setpoint.
|
void |
setContinuous(boolean continuous)
Set the PID controller to consider the input to be continuous, Rather then using the max and
min in as constraints, it considers them to be the same point and automatically calculates the
shortest route to the setpoint.
|
void |
setInputRange(double minimumInput,
double maximumInput)
Sets the maximum and minimum values expected from the input and setpoint.
|
void |
setOutputRange(double minimumOutput,
double maximumOutput)
Sets the minimum and maximum values to write.
|
void |
setPercentTolerance(double percentage)
Set the percentage error which is considered tolerable for use with OnTarget.
|
void |
setPID(double p,
double i,
double d)
Set the PID Controller gain parameters.
|
void |
setPID(double p,
double i,
double d,
double f)
Set the PID Controller gain parameters.
|
void |
setSetpoint(double setpoint)
Set the setpoint for the PIDController Clears the queue for GetAvgError().
|
void |
setTolerance(double percent)
Deprecated.
Use
setPercentTolerance(double) or setAbsoluteTolerance(double) instead. |
void |
setTolerance(PIDController.Tolerance tolerance)
Set the PID tolerance using a Tolerance object.
|
void |
setToleranceBuffer(int bufLength)
Set the number of previous error samples to average for tolerancing.
|
void |
startLiveWindowMode()
Start having this sendable object automatically respond to value changes reflect the value on
the table.
|
void |
stopLiveWindowMode()
Stop having this sendable object automatically respond to value changes.
|
void |
updateTable()
Update the table for this sendable object with the latest values.
|
public static final double kDefaultPeriod
protected PIDSource m_pidInput
protected PIDOutput m_pidOutput
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. This particularly effects calculations of
the integral and differential terms. The default is 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. This particularly effects calculations of
the integral and differential terms. The default is 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 free()
protected void calculate()
protected double calculateFeedForward()
Both of the provided feed forward calculations are velocity feed forwards. If a different feed forward calculation is desired, the user can override this function and provide his or her own. This function does no synchronization because the PIDController class only calls it in synchronized code, so be careful if calling it oneself.
If a velocity PID controller is being used, the F term should be set to 1 over the maximum setpoint for the output. If a position PID controller is being used, the F term should be set to 1 over the maximum speed for the output measured in setpoint units per this controller's update period (see the default period in this class's constructor).
public void setPID(double p, double i, double d)
setPID
in interface PIDInterface
p
- Proportional coefficienti
- Integral coefficientd
- Differential coefficientpublic void setPID(double p, double i, double d, double f)
p
- Proportional coefficienti
- Integral coefficientd
- Differential coefficientf
- Feed forward coefficientpublic double getP()
getP
in interface PIDInterface
public double getI()
getI
in interface PIDInterface
public double getD()
getD
in interface PIDInterface
public double getF()
public double get()
public void setContinuous(boolean continuous)
continuous
- Set to true turns on continuous, false turns off continuouspublic void setContinuous()
public void setInputRange(double minimumInput, double maximumInput)
minimumInput
- the minimum value expected from the inputmaximumInput
- the maximum value expected from the inputpublic void setOutputRange(double minimumOutput, double maximumOutput)
minimumOutput
- the minimum percentage to write to the outputmaximumOutput
- the maximum percentage to write to the outputpublic void setSetpoint(double setpoint)
setSetpoint
in interface PIDInterface
setpoint
- the desired setpointpublic double getSetpoint()
getSetpoint
in interface PIDInterface
public double getDeltaSetpoint()
public double getError()
getError
in interface PIDInterface
public double getAvgError()
@Deprecated public void setTolerance(double percent)
setPercentTolerance(double)
or setAbsoluteTolerance(double)
instead.percent
- error which is tolerablepublic void setTolerance(PIDController.Tolerance tolerance)
tolerance
- a tolerance object of the right type, e.g. PercentTolerance or
AbsoluteTolerancepublic void setAbsoluteTolerance(double absvalue)
absvalue
- absolute error which is tolerable in the units of the input objectpublic void setPercentTolerance(double percentage)
percentage
- percent error which is tolerablepublic void setToleranceBuffer(int bufLength)
bufLength
- Number of previous cycles to average.public boolean onTarget()
public void enable()
enable
in interface PIDInterface
public void disable()
disable
in interface PIDInterface
@Deprecated public boolean isEnable()
isEnabled()
instead.public boolean isEnabled()
isEnabled
in interface PIDInterface
public void reset()
reset
in interface PIDInterface
public java.lang.String getSmartDashboardType()
Sendable
Sendable
.getSmartDashboardType
in interface Sendable
Sendable
.public void initTable(ITable table)
Sendable
Sendable
object.protected double getContinuousError(double error)
error
- The current error of the PID controller.public ITable getTable()
Sendable
Sendable
.public void updateTable()
LiveWindowSendable
updateTable
in interface LiveWindowSendable
public void startLiveWindowMode()
LiveWindowSendable
startLiveWindowMode
in interface LiveWindowSendable
public void stopLiveWindowMode()
LiveWindowSendable
stopLiveWindowMode
in interface LiveWindowSendable