|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object edu.wpi.first.wpilibj.PIDController
public class PIDController
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
Field Summary | |
---|---|
static double |
kDefaultPeriod
|
Constructor Summary | |
---|---|
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 |
Method Summary | |
---|---|
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 |
getI()
Get the Integral coefficient |
double |
getP()
Get the Proportional coefficient |
double |
getSetpoint()
Returns the current setpoint of the PIDController |
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 |
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. |
void |
setOutputRange(double minimumOutput,
double maximumOutput)
Sets the minimum and maximum values to write. |
void |
setPID(double p,
double i,
double d)
Set the PID Controller gain parameters. |
void |
setSetpoint(double setpoint)
Set the setpoint for the PIDController |
void |
setTolerance(double percent)
Set the percentage error which is considered tolerable for use with OnTarget. |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Field Detail |
---|
public static final double kDefaultPeriod
Constructor Detail |
---|
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 valueperiod
- 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 valueMethod Detail |
---|
public void free()
public void setPID(double p, double i, double d)
p
- Proportional coefficienti
- Integral coefficientd
- Differential coefficientpublic double getP()
public double getI()
public double getD()
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 outputpublic void setOutputRange(double minimumOutput, double maximumOutput)
minimumOutput
- the minimum value to write to the outputmaximumOutput
- the maximum value to write to the outputpublic void setSetpoint(double setpoint)
setpoint
- the desired setpointpublic double getSetpoint()
public double getError()
public void setTolerance(double percent)
percent
- error which is tolerablepublic boolean onTarget()
public void enable()
public void disable()
public boolean isEnable()
public void reset()
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |