public class PIDController extends java.lang.Object implements LiveWindowSendable
| Modifier and Type | Class and Description |
|---|---|
private class |
PIDController.PIDTask
The task each PIDController runs
|
static interface |
PIDController.Tolerance
Interface for representing the error and tolerance
of the PID
|
| Modifier and Type | Field and Description |
|---|---|
static double |
DEFAULT_PERIOD |
private boolean |
m_continuous |
(package private) java.util.Timer |
m_controlLoop |
private double |
m_D |
private boolean |
m_enabled |
private double |
m_error |
private double |
m_F |
private double |
m_I |
private static int |
m_instances |
private ITableListener |
m_listener |
private double |
m_maxInput |
private double |
m_maxOutput |
private double |
m_minInput |
private double |
m_minOutput |
private double |
m_P |
private double |
m_prevError |
private double |
m_result |
private double |
m_setpoint |
(package private) PIDSink |
m_sink |
(package private) PIDSource |
m_source |
private ITable |
m_table |
private PIDController.Tolerance |
m_tolerance |
private double |
m_totalError |
| Constructor and Description |
|---|
PIDController(double p,
double i,
double d,
double f,
PIDSource source,
PIDSink sink)
Allocate a PID object with the given constants for P, I, D, using a 50ms period.
|
PIDController(double p,
double i,
double d,
double f,
PIDSource source,
PIDSink sink,
double period)
Allocate a PID object with the given constants for P, I, D, and F
|
PIDController(double p,
double i,
double d,
PIDSource source,
PIDSink sink)
Allocate a PID object with the given constants for P, I, D, using a 50ms period.
|
PIDController(double p,
double i,
double d,
PIDSource source,
PIDSink sink,
double period)
Allocate a PID object with the given constants for P, I, D and period
|
| Modifier and Type | Method and Description |
|---|---|
private void |
calculate()
Read the input, calculate the output accordingly, and write to the output.
|
void |
disable()
Stop running the PIDController, this sets the output to zero before stopping.
|
void |
enable()
Begin running the PIDController
|
void |
free() |
double |
get()
Return the current PID result
This is always centered on zero and constrained the the max and min outs
|
double |
getD()
Get the Differential coefficient
|
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() |
ITable |
getTable() |
void |
initTable(ITable table) |
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 min,
double max)
Sets the maximum and minimum values expected from the input and setpoint.
|
void |
setOutputRange(double min,
double max)
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 point)
Set the setpoint for the PIDController
|
void |
setTolerance(PIDController.Tolerance tolerance)
Set the PID tolerance using a Tolerance object.
|
void |
startLiveWindowMode() |
void |
stopLiveWindowMode() |
void |
updateTable() |
public static final double DEFAULT_PERIOD
private static int m_instances
private double m_P
private double m_I
private double m_D
private double m_F
private double m_maxOutput
private double m_minOutput
private double m_maxInput
private double m_minInput
private boolean m_continuous
private boolean m_enabled
private double m_prevError
private double m_totalError
private PIDController.Tolerance m_tolerance
private double m_setpoint
private double m_error
private double m_result
PIDSource m_source
PIDSink m_sink
java.util.Timer m_controlLoop
private ITable m_table
private final ITableListener m_listener
public PIDController(double p,
double i,
double d,
double f,
PIDSource source,
PIDSink sink,
double period)
p - the proportional coefficienti - the integral coefficientd - the derivative coefficientf - the feed forward termsource - The PIDSource object that is used to get valuessink - 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 p,
double i,
double d,
PIDSource source,
PIDSink sink,
double period)
p - the proportional coefficienti - the integral coefficientd - the derivative coefficientsource - the PIDSource object that is used to get valuessink - 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 p,
double i,
double d,
PIDSource source,
PIDSink sink)
p - the proportional coefficienti - the integral coefficientd - the derivative coefficientsource - The PIDSource object that is used to get valuessink - The PIDOutput object that is set to the output percentagepublic PIDController(double p,
double i,
double d,
double f,
PIDSource source,
PIDSink sink)
p - the proportional coefficienti - the integral coefficientd - the derivative coefficientf - the feed forward termsource - The PIDSource object that is used to get valuessink - The PIDOutput object that is set to the output percentagepublic void free()
private void calculate()
public void setPID(double p,
double i,
double d)
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()
public double getI()
public double getD()
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 min,
double max)
min - the minimum value expected from the inputmax - the maximum value expected from the inputpublic void setOutputRange(double min,
double max)
min - the minimum percentage to write to the outputmax - the maximum percentage to write to the outputpublic void setSetpoint(double point)
point - the desired setpointpublic double getSetpoint()
public double getError()
public void setTolerance(PIDController.Tolerance tolerance)
tolerance - a tolerance object of the right type, e.g. PercentTolerance or AbsoluteTolerancepublic void setPercentTolerance(double percentage)
percentage - percent error which is tolerablepublic void setAbsoluteTolerance(double absValue)
absValue - absolute error which is tolerable in the units of the input objectpublic boolean onTarget()
public void enable()
public void disable()
public boolean isEnabled()
public void reset()
public java.lang.String getSmartDashboardType()
getSmartDashboardType in interface Sendablepublic void updateTable()
updateTable in interface UpdatingSendablepublic void startLiveWindowMode()
startLiveWindowMode in interface LiveWindowSendablepublic void stopLiveWindowMode()
stopLiveWindowMode in interface LiveWindowSendable