|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectedu.wpi.first.wpilibj.PIDController
edu.wpi.first.wpilibj.smartdashboard.SendablePIDController
public class SendablePIDController
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.
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 |
---|
public SendablePIDController(double p, double i, double d, PIDSource source, PIDOutput output)
p
- the proportional coefficienti
- the integral coefficientd
- the derivative coefficientsource
- The PIDSource object that is used to get valuesoutput
- The PIDOutput object that is set to the output valuepublic SendablePIDController(double p, double i, double d, PIDSource source, PIDOutput output, double period)
p
- the proportional coefficienti
- the integral coefficientd
- the derivative coefficientsource
- The PIDSource object that is used to get valuesoutput
- The PIDOutput object that is set to the output valueperiod
- the loop time for doing calculations. This particularly effects calculations of the
integral and differential terms. The default is 50ms.Method Detail |
---|
public void setSetpoint(double setpoint)
setSetpoint
in class PIDController
setpoint
- the desired setpointpublic void setPID(double p, double i, double d)
PIDController
setPID
in class PIDController
p
- Proportional coefficienti
- Integral coefficientd
- Differential coefficientpublic void enable()
PIDController
enable
in class PIDController
public void disable()
PIDController
disable
in class PIDController
public java.lang.String getType()
SmartDashboardData
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()
.
getType
in interface SmartDashboardData
public NetworkTable getTable()
SmartDashboardData
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
getTable
in interface SmartDashboardData
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |