"

2013 FRC Java API

"

edu.wpi.first.wpilibj.command
Class PIDCommand

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

public abstract class PIDCommand
extends Command
implements Sendable

This class defines a Command which interacts heavily with a PID loop.

It provides some convenience methods to run an internal PIDController. It will also start and stop said PIDController when the PIDCommand is first initialized and ended/interrupted.

Author:
Joe Grinstead

Constructor Summary
PIDCommand(double p, double i, double d)
          Instantiates a PIDCommand that will use the given p, i and d values.
PIDCommand(double p, double i, double d, double period)
          Instantiates a PIDCommand that will use the given p, i and d values.
PIDCommand(String name, double p, double i, double d)
          Instantiates a PIDCommand that will use the given p, i and d values.
PIDCommand(String name, double p, double i, double d, double period)
          Instantiates a PIDCommand that will use the given p, i and d values.
 
Method Summary
protected  PIDController getPIDController()
          Returns the PIDController used by this PIDCommand.
protected  double getPosition()
          Returns the current position
protected  double getSetpoint()
          Returns the setpoint.
 String getSmartDashboardType()
           
 void initTable(ITable table)
          Initializes a table for this sendable object.
protected abstract  double returnPIDInput()
          Returns the input for the pid loop.
protected  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.Command
cancel, doesRequire, end, execute, getGroup, getName, getTable, initialize, interrupted, isCanceled, isFinished, isInterruptible, isRunning, isTimedOut, requires, setInterruptible, setRunWhenDisabled, setTimeout, start, timeSinceInitialized, toString, willRunWhenDisabled
 
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

PIDCommand

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

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

PIDCommand

public PIDCommand(String name,
                  double p,
                  double i,
                  double d,
                  double period)
Instantiates a PIDCommand 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

PIDCommand

public PIDCommand(double p,
                  double i,
                  double d)
Instantiates a PIDCommand 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

PIDCommand

public PIDCommand(double p,
                  double i,
                  double d,
                  double period)
Instantiates a PIDCommand 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 PIDCommand. 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 PIDCommand

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

protected 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

protected double getSetpoint()
Returns the setpoint.

Returns:
the setpoint

getPosition

protected double getPosition()
Returns the current position

Returns:
the current position

returnPIDInput

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

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

All subclasses of PIDCommand must override this method.

This method will be called in a different thread then the Scheduler thread.

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 PIDCommand must override this method.

This method will be called in a different thread then the Scheduler thread.

Parameters:
output - the value the pid loop calculated

getSmartDashboardType

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

"

2013 FRC Java API

"

"
For updated information see the Java FRC site
"