"

2013 FRC Java API

"

edu.wpi.first.wpilibj
Class PIDController

java.lang.Object
  extended by edu.wpi.first.wpilibj.PIDController
All Implemented Interfaces:
LiveWindowSendable, IDevice, IUtility, Sendable

public class PIDController
extends Object
implements IUtility, LiveWindowSendable

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


Nested Class Summary
 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.
 
Field Summary
static double kDefaultPeriod
           
 
Constructor Summary
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
 
Method Summary
protected  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()
          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()
           
 ITable getTable()
          
 void initTable(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.
 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 setTolerance(Tolerance), i.e. setTolerance(new PIDController.PercentageTolerance(15))
 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.
 
Methods inherited from class java.lang.Object
equals, 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,
                     double Kf,
                     PIDSource source,
                     PIDOutput output,
                     double period)
Allocate a PID object with the given constants for P, I, D, and F

Parameters:
Kp - the proportional coefficient
Ki - the integral coefficient
Kd - the derivative coefficient
Kf - the feed forward term
source - The PIDSource object that is used to get values
output - The PIDOutput object that is set to the output percentage
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,
                     double period)
Allocate a PID object with the given constants for P, I, D and period

Parameters:
Kp -
Ki -
Kd -
source -
output -
period -

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 percentage

PIDController

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

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 percentage
Method Detail

free

public void free()
Free the PID object


calculate

protected void calculate()
Read the input, calculate the output accordingly, and write to the output. This should only be called by the PIDTask and is created during initialization.


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

setPID

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

Parameters:
p - Proportional coefficient
i - Integral coefficient
d - Differential coefficient
f - Feed forward 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

getF

public double getF()
Get the Feed forward coefficient

Returns:
feed forward 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 percentage expected from the input
maximumInput - the maximum percentage expected from the output

setOutputRange

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

Parameters:
minimumOutput - the minimum percentage to write to the output
maximumOutput - the maximum percentage 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)
Deprecated. Use setTolerance(Tolerance), i.e. setTolerance(new PIDController.PercentageTolerance(15))

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

Parameters:
percent - error which is tolerable

setAbsoluteTolerance

public void setAbsoluteTolerance(double absvalue)
Set the absolute error which is considered tolerable for use with OnTarget.

Parameters:
absolute - error which is tolerable in the units of the input object

setPercentTolerance

public void setPercentTolerance(double percentage)
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.


getSmartDashboardType

public String getSmartDashboardType()
Specified by:
getSmartDashboardType in interface Sendable
Returns:
the string representation of the named data type that will be used by the smart dashboard for this sendable

initTable

public void initTable(ITable table)
Description copied from interface: Sendable
Initializes a table for this sendable object.

Specified by:
initTable in interface Sendable
Parameters:
table - The table to put the values in.

getTable

public ITable getTable()

Specified by:
getTable in interface Sendable
Returns:
the table that is currently associated with the sendable

updateTable

public void updateTable()
Update the table for this sendable object with the latest values.

Specified by:
updateTable in interface LiveWindowSendable

startLiveWindowMode

public void startLiveWindowMode()
Start having this sendable object automatically respond to value changes reflect the value on the table.

Specified by:
startLiveWindowMode in interface LiveWindowSendable

stopLiveWindowMode

public void stopLiveWindowMode()
Stop having this sendable object automatically respond to value changes.

Specified by:
stopLiveWindowMode in interface LiveWindowSendable

"

2013 FRC Java API

"

"
For updated information see the Java FRC site
"