|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Object edu.wpi.first.wpilibj.command.Command edu.wpi.first.wpilibj.command.PIDCommand
public abstract class PIDCommand
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.
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(java.lang.String name,
double p,
double i,
double d)
Instantiates a PIDCommand that will use the given p, i and d values. |
|
PIDCommand(java.lang.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. |
NetworkTable |
getTable()
Returns the NetworkTable associated with the data. |
java.lang.String |
getType()
Returns the type of the data. |
protected abstract double |
returnPIDInput()
Returns the input for the pid loop. |
protected 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.Command |
---|
cancel, doesRequire, end, execute, getGroup, getName, grabTable, initialize, interrupted, isCanceled, isFinished, isInterruptible, isRunning, isTimedOut, requires, setInterruptible, setRunWhenDisabled, setTimeout, start, timeSinceInitialized, toString, willRunWhenDisabled |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait |
Constructor Detail |
---|
public PIDCommand(java.lang.String name, double p, double i, double d)
PIDCommand
that will use the given p, i and d values.
name
- the name of the commandp
- the proportional valuei
- the integral valued
- the derivative valuepublic PIDCommand(java.lang.String name, double p, double i, double d, double period)
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.
name
- the namep
- the proportional valuei
- the integral valued
- the derivative valueperiod
- the time (in seconds) between calculationspublic PIDCommand(double p, double i, double d)
PIDCommand
that will use the given p, i and d values.
It will use the class name as its name.
p
- the proportional valuei
- the integral valued
- the derivative valuepublic PIDCommand(double p, double i, double d, double period)
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.
p
- the proportional valuei
- the integral valued
- the derivative valueperiod
- the time (in seconds) between calculationsMethod Detail |
---|
protected PIDController getPIDController()
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(...)
.
PIDController
used by this PIDCommand
public void setSetpointRelative(double deltaSetpoint)
setRange(...)
was used,
then the bounds will still be honored by this method.
deltaSetpoint
- the change in the setpointprotected void setSetpoint(double setpoint)
setRange(...)
was called,
then the given setpoint
will be trimmed to fit within the range.
setpoint
- the new setpointprotected double getSetpoint()
protected double getPosition()
protected void setSetpointRange(double a, double b)
setSetpoint(...)
will force the setpoint within the given values.
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)protected abstract double returnPIDInput()
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.
protected abstract void usePIDOutput(double output)
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.
output
- the value the pid loop calculatedpublic 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
getType
in class Command
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
getTable
in class Command
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |