|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectedu.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. |
java.lang.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 |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait |
Methods inherited from interface edu.wpi.first.wpilibj.Sendable |
---|
getTable |
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 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 getSmartDashboardType()
getSmartDashboardType
in interface Sendable
getSmartDashboardType
in class Command
public void initTable(ITable table)
Sendable
initTable
in interface Sendable
initTable
in class Command
table
- The table to put the values in.
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |