public abstract class PIDCommand extends Command implements Sendable
| Modifier and Type | Field and Description |
|---|---|
(package private) PIDController |
m_controller |
(package private) PIDSink |
m_sink |
(package private) PIDSource |
m_source |
m_locked, m_nextCommand, m_previousCommand, m_running, m_state| Constructor and Description |
|---|
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. |
| Modifier and Type | Method and Description |
|---|---|
(package private) void |
_end()
End_impl.
|
(package private) void |
_initialize()
Initialize_impl.
|
(package private) void |
_interrupted()
Interrupted_impl.
|
protected PIDController |
getController()
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) |
protected abstract double |
returnPIDInput()
Returns the input for the pid loop.
|
protected void |
setInputRange(double min,
double max)
Sets the maximum and minimum values expected from the input and setpoint.
|
protected void |
setOutputRange(double min,
double max)
Sets the maximum and minimum values to write.
|
protected void |
setSetpoint(double point)
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.
|
_cancel, _execute, cancel, doesRequire, end, execute, getGroup, getName, getRequirements, getTable, initialize, interrupted, isCanceled, isFinished, isInterruptible, isRunning, isTimedOut, removed, requires, run, setCancelOnModeSwitch, setInterruptible, setParent, setRunWhenDisabled, setTimeout, start, startRunning, timeSinceInitialized, toString, willCancelOnModeSwitch, willRunWhenDisabledfinal PIDController m_controller
final PIDSink m_sink
final PIDSource m_source
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 calculationsprotected PIDController getController()
PIDController used by this PIDCommand.
Use this if you would like to fine tune the pid loop.PIDController used by this PIDCommandfinal void _initialize()
Command_initialize in class Commandfinal void _end()
Commandfinal void _interrupted()
Command_interrupted in class Commandpublic final void setSetpointRelative(double deltaSetpoint)
setInputRange(...) was used,
then the bounds will still be honored by this method.deltaSetpoint - the change in the setpointprotected final void setSetpoint(double point)
setInputRange(...)
was called,
then the given setpoint
will be trimmed to fit within the range.setpoint - the new setpointprotected final double getSetpoint()
protected final double getPosition()
protected final void setInputRange(double min,
double max)
min - the minimum value expected from the input and setpointmax - the maximum value expected from the input and setpointprotected final void setOutputRange(double min,
double max)
min - the minimum value to write to the outputmax - the maximum value to write to the outputprotected 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 final java.lang.String getSmartDashboardType()
getSmartDashboardType in interface SendablegetSmartDashboardType in class Command