edu.wpi.first.wpilibj
Class PIDController

java.lang.Object
  extended by edu.wpi.first.wpilibj.PIDController
All Implemented Interfaces:
IDevice, IUtility
Direct Known Subclasses:
SendablePIDController

public class PIDController
extends java.lang.Object
implements IUtility

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

kDefaultPeriod

public static final double kDefaultPeriod
See Also:
Constant Field Values
Constructor Detail

PIDController

public 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

Parameters:
Kp - the proportional coefficient
Ki - the integral coefficient
Kd - the derivative coefficient
source - The PIDSource object that is used to get values
output - The PIDOutput object that is set to the output value
period - the loop time for doing calculations. This particularly effects calculations of the integral and differential terms. The default is 50ms.

PIDController

public 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.

Parameters:
Kp - the proportional coefficient
Ki - the integral coefficient
Kd - the derivative coefficient
source - The PIDSource object that is used to get values
output - The PIDOutput object that is set to the output value
Method Detail

free

public void free()
Free the PID object


setPID

public void setPID(double p,
                   double i,
                   double d)
Set the PID Controller gain parameters. Set the proportional, integral, and differential coefficients.

Parameters:
p - Proportional coefficient
i - Integral coefficient
d - Differential coefficient

getP

public double getP()
Get the Proportional coefficient

Returns:
proportional coefficient

getI

public double getI()
Get the Integral coefficient

Returns:
integral coefficient

getD

public double getD()
Get the Differential coefficient

Returns:
differential coefficient

get

public double get()
Return the current PID result This is always centered on zero and constrained the the max and min outs

Returns:
the latest calculated output

setContinuous

public 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.

Parameters:
continuous - Set to true turns on continuous, false turns off continuous

setContinuous

public 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.


setInputRange

public void setInputRange(double minimumInput,
                          double maximumInput)
Sets the maximum and minimum values expected from the input.

Parameters:
minimumInput - the minimum value expected from the input
maximumInput - the maximum value expected from the output

setOutputRange

public void setOutputRange(double minimumOutput,
                           double maximumOutput)
Sets the minimum and maximum values to write.

Parameters:
minimumOutput - the minimum value to write to the output
maximumOutput - the maximum value to write to the output

setSetpoint

public void setSetpoint(double setpoint)
Set the setpoint for the PIDController

Parameters:
setpoint - the desired setpoint

getSetpoint

public double getSetpoint()
Returns the current setpoint of the PIDController

Returns:
the current setpoint

getError

public double getError()
Returns the current difference of the input from the setpoint

Returns:
the current error

setTolerance

public void setTolerance(double percent)
Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 = 15 percent)

Parameters:
percent - error which is tolerable

onTarget

public boolean onTarget()
Return true if the error is within the percentage of the total input range, determined by setTolerance. This assumes that the maximum and minimum input were set using setInput.

Returns:
true if the error is less than the tolerance

enable

public void enable()
Begin running the PIDController


disable

public void disable()
Stop running the PIDController, this sets the output to zero before stopping.


isEnable

public boolean isEnable()
Return true if PIDController is enabled.


reset

public void reset()
Reset the previous error,, the integral term, and disable the controller.