public class PIDController extends Object implements LiveWindowSendable
Modifier and Type | Class and Description |
---|---|
class |
PIDController.AbsoluteTolerance |
class |
PIDController.NullTolerance |
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 |
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 |
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 |
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
|
String |
getSmartDashboardType() |
edu.wpi.first.wpilibj.tables.ITable |
getTable() |
void |
initTable(edu.wpi.first.wpilibj.tables.ITable table)
Initializes a table for this sendable object.
|
boolean |
isEnable()
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
|
void |
setTolerance(double percent)
Deprecated.
Use
setPercentTolerance(double) or setAbsoluteTolerance(double) instead. |
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
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()
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 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)
setpoint
- the desired setpointpublic double getSetpoint()
public double getError()
@Deprecated public void setTolerance(double percent)
setPercentTolerance(double)
or setAbsoluteTolerance(double)
instead.percent
- error which is tolerablepublic 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 boolean onTarget()
public void enable()
public void disable()
public boolean isEnable()
public void reset()
public String getSmartDashboardType()
getSmartDashboardType
in interface Sendable
public void initTable(edu.wpi.first.wpilibj.tables.ITable table)
Sendable
public edu.wpi.first.wpilibj.tables.ITable getTable()
public void updateTable()
updateTable
in interface LiveWindowSendable
public void startLiveWindowMode()
startLiveWindowMode
in interface LiveWindowSendable
public void stopLiveWindowMode()
stopLiveWindowMode
in interface LiveWindowSendable
Copyright © 2015. All rights reserved.