edu.wpi.first.wpilibj.smartdashboard
Class SendablePIDController

java.lang.Object
  extended by edu.wpi.first.wpilibj.PIDController
      extended by edu.wpi.first.wpilibj.smartdashboard.SendablePIDController
All Implemented Interfaces:
IDevice, IUtility, SmartDashboardData

public class SendablePIDController
extends PIDController
implements SmartDashboardData

A SendablePIDController is a PIDController that can be sent over to the SmartDashboard using the putData(...) method.

It is useful if you want to test values of a PIDController without having to recompile code between tests. Also, consider using Preferences to save the important values between matches.

Author:
Joe Grinstead
See Also:
SmartDashboard

Field Summary
 
Fields inherited from class edu.wpi.first.wpilibj.PIDController
kDefaultPeriod
 
Constructor Summary
SendablePIDController(double p, double i, double d, PIDSource source, PIDOutput output)
          Allocate a PID object with the given constants for P, I, D, using a 50ms period.
SendablePIDController(double p, double i, double d, 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
 NetworkTable getTable()
          Returns the NetworkTable associated with the data.
 java.lang.String getType()
          Returns the type of the data.
 void setPID(double p, double i, double d)
          Set the PID Controller gain parameters.
 void setSetpoint(double setpoint)
          Set the setpoint for the PIDController
 
Methods inherited from class edu.wpi.first.wpilibj.PIDController
free, get, getD, getError, getI, getP, getSetpoint, isEnable, onTarget, reset, setContinuous, setContinuous, setInputRange, setOutputRange, setTolerance
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

SendablePIDController

public SendablePIDController(double p,
                             double i,
                             double d,
                             PIDSource source,
                             PIDOutput output)
Allocate a PID object with the given constants for P, I, D, using a 50ms period.

Parameters:
p - the proportional coefficient
i - the integral coefficient
d - the derivative coefficient
source - The PIDSource object that is used to get values
output - The PIDOutput object that is set to the output value

SendablePIDController

public SendablePIDController(double p,
                             double i,
                             double d,
                             PIDSource source,
                             PIDOutput output,
                             double period)
Allocate a PID object with the given constants for P, I, D

Parameters:
p - the proportional coefficient
i - the integral coefficient
d - 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.
Method Detail

setSetpoint

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

Overrides:
setSetpoint in class PIDController
Parameters:
setpoint - the desired setpoint

setPID

public void setPID(double p,
                   double i,
                   double d)
Description copied from class: PIDController
Set the PID Controller gain parameters. Set the proportional, integral, and differential coefficients.

Overrides:
setPID in class PIDController
Parameters:
p - Proportional coefficient
i - Integral coefficient
d - Differential coefficient

enable

public void enable()
Description copied from class: PIDController
Begin running the PIDController

Overrides:
enable in class PIDController

disable

public void disable()
Description copied from class: PIDController
Stop running the PIDController, this sets the output to zero before stopping.

Overrides:
disable in class 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
Returns:
the type of the data

getTable

public NetworkTable getTable()
Description copied from interface: SmartDashboardData
Returns the NetworkTable associated with the data. The table should contain all the information the desktop version of SmartDashboard needs to interact with the object. The data should both keep the table up-to-date and also react to changes that the SmartDashboard might make.

For instance, the SendablePIDController will put its p, i and d values into its table and will change them if the table receives new values.

This method should return the same table between calls

Specified by:
getTable in interface SmartDashboardData
Returns:
the table that represents this data