Package edu.wpi.first.wpilibj2.command
Class PIDCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.CommandBase
edu.wpi.first.wpilibj2.command.PIDCommand
- All Implemented Interfaces:
Command
public class PIDCommand extends CommandBase
A command that controls an output with a
PIDController
. Runs forever by default - to add
exit conditions and/or other behavior, subclass this class. The controller calculation and
output are performed synchronously in the command's execute() method.-
Constructor Summary
Constructors Constructor Description PIDCommand(PIDController controller, java.util.function.DoubleSupplier measurementSource, double setpoint, java.util.function.DoubleConsumer useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a PIDController.PIDCommand(PIDController controller, java.util.function.DoubleSupplier measurementSource, java.util.function.DoubleSupplier setpointSource, java.util.function.DoubleConsumer useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a PIDController. -
Method Summary
Modifier and Type Method Description void
end(boolean interrupted)
The action to take when the command ends.void
execute()
The main body of a command.PIDController
getController()
Returns the PIDController used by the command.void
initialize()
The initial subroutine of a command.void
setOutput(java.util.function.DoubleConsumer useOutput)
Sets the function that uses the output of the PIDController.void
setSetpoint(double setpoint)
Sets the setpoint for the controller to a constant value.void
setSetpoint(java.util.function.DoubleSupplier setpointSource)
Sets the setpoint for the controller to track the given source.void
setSetpointRelative(double relativeReference)
Sets the setpoint for the controller to a constant value relative (i.e.Methods inherited from class edu.wpi.first.wpilibj2.command.CommandBase
addRequirements, getRequirements
Methods inherited from class java.lang.Object
equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface edu.wpi.first.wpilibj2.command.Command
alongWith, andThen, asProxy, beforeStarting, cancel, deadlineWith, getName, hasRequirement, interruptOn, isFinished, isScheduled, perpetually, raceWith, runsWhenDisabled, schedule, schedule, whenFinished, withTimeout
-
Constructor Details
-
PIDCommand
public PIDCommand(PIDController controller, java.util.function.DoubleSupplier measurementSource, java.util.function.DoubleSupplier setpointSource, java.util.function.DoubleConsumer useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a PIDController.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablesetpointSource
- the controller's setpointuseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
PIDCommand
public PIDCommand(PIDController controller, java.util.function.DoubleSupplier measurementSource, double setpoint, java.util.function.DoubleConsumer useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a PIDController.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablesetpoint
- the controller's setpointuseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
-
Method Details
-
initialize
public void initialize()Description copied from interface:Command
The initial subroutine of a command. Called once when the command is initially scheduled. -
execute
public void execute()Description copied from interface:Command
The main body of a command. Called repeatedly while the command is scheduled. -
end
public void end(boolean interrupted)Description copied from interface:Command
The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.- Parameters:
interrupted
- whether the command was interrupted/canceled
-
setOutput
public final void setOutput(java.util.function.DoubleConsumer useOutput)Sets the function that uses the output of the PIDController.- Parameters:
useOutput
- The function that uses the output.
-
getController
Returns the PIDController used by the command.- Returns:
- The PIDController
-
setSetpoint
public void setSetpoint(java.util.function.DoubleSupplier setpointSource)Sets the setpoint for the controller to track the given source.- Parameters:
setpointSource
- The setpoint source
-
setSetpoint
public void setSetpoint(double setpoint)Sets the setpoint for the controller to a constant value.- Parameters:
setpoint
- The setpoint
-
setSetpointRelative
public void setSetpointRelative(double relativeReference)Sets the setpoint for the controller to a constant value relative (i.e. added to) the current setpoint.- Parameters:
relativeReference
- The change in setpoint
-