"

2013 FRC Java API

"

edu.wpi.first.wpilibj.command
Class PIDSubsystem

java.lang.Object
  extended by edu.wpi.first.wpilibj.command.Subsystem
      extended by edu.wpi.first.wpilibj.command.PIDSubsystem
All Implemented Interfaces:
NamedSendable, Sendable

public abstract class PIDSubsystem
extends Subsystem
implements Sendable

This class is designed to handle the case where there is a Subsystem which uses a single PIDController almost constantly (for instance, an elevator which attempts to stay at a constant height).

It provides some convenience methods to run an internal PIDController. It also allows access to the internal PIDController in order to give total control to the programmer.

Author:
Joe Grinstead

Constructor Summary
PIDSubsystem(double p, double i, double d)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(double p, double i, double d, double period)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(double p, double i, double d, double period, double f)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(String name, double p, double i, double d)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(String name, double p, double i, double d, double f)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(String name, double p, double i, double d, double f, double period)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
 
Method Summary
 void disable()
          Disables the internal PIDController
 void enable()
          Enables the internal PIDController
 PIDController getPIDController()
          Returns the PIDController used by this PIDSubsystem.
 double getPosition()
          Returns the current position
 double getSetpoint()
          Returns the setpoint.
 String getSmartDashboardType()
           
 void initTable(ITable table)
          Initializes a table for this sendable object.
 boolean onTarget()
          Return true if the error is within the percentage of the total input range, determined by setTolerance.
protected abstract  double returnPIDInput()
          Returns the input for the pid loop.
 void setAbsoluteTolerance(double t)
          Set the absolute error which is considered tolerable for use with OnTarget.
 void setInputRange(double minimumInput, double maximumInput)
          Sets the maximum and minimum values expected from the input.
 void setPercentTolerance(double p)
          Set the percentage error which is considered tolerable for use with OnTarget.
 void setSetpoint(double setpoint)
          Sets the setpoint to the given value.
 void setSetpointRelative(double deltaSetpoint)
          Adds the given value to the setpoint.
protected abstract  void usePIDOutput(double output)
          Uses the value that the pid loop calculated.
 
Methods inherited from class edu.wpi.first.wpilibj.command.Subsystem
getCurrentCommand, getDefaultCommand, getName, getTable, initDefaultCommand, setDefaultCommand, toString
 
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, wait, wait, wait
 
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
getTable
 

Constructor Detail

PIDSubsystem

public PIDSubsystem(String name,
                    double p,
                    double i,
                    double d)
Instantiates a PIDSubsystem that will use the given p, i and d values.

Parameters:
name - the name
p - the proportional value
i - the integral value
d - the derivative value

PIDSubsystem

public PIDSubsystem(String name,
                    double p,
                    double i,
                    double d,
                    double f)
Instantiates a PIDSubsystem that will use the given p, i and d values.

Parameters:
name - the name
p - the proportional value
i - the integral value
d - the derivative value
f - the feed forward value

PIDSubsystem

public PIDSubsystem(String name,
                    double p,
                    double i,
                    double d,
                    double f,
                    double period)
Instantiates a PIDSubsystem that will use the given p, i and d values. It will also space the time between PID loop calculations to be equal to the given period.

Parameters:
name - the name
p - the proportional value
i - the integral value
d - the derivative value
period - the time (in seconds) between calculations

PIDSubsystem

public PIDSubsystem(double p,
                    double i,
                    double d)
Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name.

Parameters:
p - the proportional value
i - the integral value
d - the derivative value

PIDSubsystem

public PIDSubsystem(double p,
                    double i,
                    double d,
                    double period,
                    double f)
Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name. It will also space the time between PID loop calculations to be equal to the given period.

Parameters:
p - the proportional value
i - the integral value
d - the derivative value
f - the feed forward coefficient
period - the time (in seconds) between calculations

PIDSubsystem

public PIDSubsystem(double p,
                    double i,
                    double d,
                    double period)
Instantiates a PIDSubsystem that will use the given p, i and d values. It will use the class name as its name. It will also space the time between PID loop calculations to be equal to the given period.

Parameters:
p - the proportional value
i - the integral value
d - the derivative value
period - the time (in seconds) between calculations
Method Detail

getPIDController

public PIDController getPIDController()
Returns the PIDController used by this PIDSubsystem. Use this if you would like to fine tune the pid loop.

Notice that calling setSetpoint(...) on the controller will not result in the setpoint being trimmed to be in the range defined by setSetpointRange(...).

Returns:
the PIDController used by this PIDSubsystem

setSetpointRelative

public void setSetpointRelative(double deltaSetpoint)
Adds the given value to the setpoint. If setRange(...) was used, then the bounds will still be honored by this method.

Parameters:
deltaSetpoint - the change in the setpoint

setSetpoint

public void setSetpoint(double setpoint)
Sets the setpoint to the given value. If setRange(...) was called, then the given setpoint will be trimmed to fit within the range.

Parameters:
setpoint - the new setpoint

getSetpoint

public double getSetpoint()
Returns the setpoint.

Returns:
the setpoint

getPosition

public double getPosition()
Returns the current position

Returns:
the current position

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

setAbsoluteTolerance

public void setAbsoluteTolerance(double t)
Set the absolute error which is considered tolerable for use with OnTarget. The value is in the same range as the PIDInput values.

Parameters:
t - A PIDController.Tolerance object instance that is for example AbsoluteTolerance or PercentageTolerance. E.g. setTolerance(new PIDController.AbsoluteTolerance(0.1))

setPercentTolerance

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

Parameters:
t - A PIDController.Tolerance object instance that is for example AbsoluteTolerance or PercentageTolerance. E.g. setTolerance(new PIDController.AbsoluteTolerance(0.1))

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

returnPIDInput

protected abstract double returnPIDInput()
Returns the input for the pid loop.

It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then it should return the angle of the gyro

All subclasses of PIDSubsystem must override this method.

Returns:
the value the pid loop should use as input

usePIDOutput

protected abstract void usePIDOutput(double output)
Uses the value that the pid loop calculated. The calculated value is the "output" parameter. This method is a good time to set motor values, maybe something along the lines of driveline.tankDrive(output, -output)

All subclasses of PIDSubsystem must override this method.

Parameters:
output - the value the pid loop calculated

enable

public void enable()
Enables the internal PIDController


disable

public void disable()
Disables the internal PIDController


getSmartDashboardType

public String getSmartDashboardType()
Specified by:
getSmartDashboardType in interface Sendable
Overrides:
getSmartDashboardType in class Subsystem
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
Overrides:
initTable in class Subsystem
Parameters:
table - The table to put the values in.

"

2013 FRC Java API

"

"
For updated information see the Java FRC site
"