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:
SmartDashboardData, SmartDashboardNamedData

public abstract class PIDSubsystem
extends Subsystem

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(java.lang.String name, double p, double i, double d)
          Instantiates a PIDSubsystem that will use the given p, i and d values.
PIDSubsystem(java.lang.String name, double p, double i, double d, 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
protected  PIDController getPIDController()
          Returns the PIDController used by this PIDSubsystem.
 double getPosition()
          Returns the current position
 double getSetpoint()
          Returns the setpoint.
 java.lang.String getType()
          Returns the type of the data.
protected abstract  double returnPIDInput()
          Returns the input for the pid loop.
 void setSetpoint(double setpoint)
          Sets the setpoint to the given value.
protected  void setSetpointRange(double a, double b)
          Sets the range that the setpoint may be in.
 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
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
 

Constructor Detail

PIDSubsystem

public PIDSubsystem(java.lang.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(java.lang.String name,
                    double p,
                    double i,
                    double d,
                    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)
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

protected 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

setSetpointRange

protected void setSetpointRange(double a,
                                double b)
Sets the range that the setpoint may be in. If this method is called, all subsequent calls to setSetpoint(...) will force the setpoint within the given values.

Parameters:
a - the first value (can be the min or max, it doesn't matter)
b - the second value (can be the min or max, it doesn't matter)

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


getType

public java.lang.String getType()
Description copied from interface: SmartDashboardData
Returns the type of the data. This is used by the SmartDashboard on the desktop to determine what to do with the table returned by getTable().

For instance, if the type was "Button", then the SmartDashboard would show the data as a button on the desktop and would know to look at and modify the "pressed" field in the NetworkTable returned by getTable().

Specified by:
getType in interface SmartDashboardData
Overrides:
getType in class Subsystem
Returns:
the type of the data