Package edu.wpi.first.wpilibj2.command
Class PIDCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
edu.wpi.first.wpilibj2.command.PIDCommand
- All Implemented Interfaces:
Sendable
public class PIDCommand extends Command
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.
This class is provided by the NewCommands VendorDep
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Field Summary
Fields Modifier and Type Field Description protected PIDController
m_controller
PID controller.protected DoubleSupplier
m_measurement
Measurement getter.protected DoubleSupplier
m_setpoint
Setpoint getter.protected DoubleConsumer
m_useOutput
PID controller output consumer. -
Constructor Summary
Constructors Constructor Description PIDCommand(PIDController controller, DoubleSupplier measurementSource, double setpoint, DoubleConsumer useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a PIDController.PIDCommand(PIDController controller, DoubleSupplier measurementSource, DoubleSupplier setpointSource, 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.Methods inherited from class edu.wpi.first.wpilibj2.command.Command
addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isFinished, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, runsWhenDisabled, schedule, setName, setSubsystem, unless, until, withInterruptBehavior, withName, withTimeout
-
Field Details
-
m_controller
PID controller. -
m_measurement
Measurement getter. -
m_setpoint
Setpoint getter. -
m_useOutput
PID controller output consumer.
-
-
Constructor Details
-
PIDCommand
public PIDCommand(PIDController controller, DoubleSupplier measurementSource, DoubleSupplier setpointSource, 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, DoubleSupplier measurementSource, double setpoint, 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
Description copied from class:Command
The initial subroutine of a command. Called once when the command is initially scheduled.- Overrides:
initialize
in classCommand
-
execute
Description copied from class:Command
The main body of a command. Called repeatedly while the command is scheduled. -
end
Description copied from class:Command
The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.Do not schedule commands here that share requirements with this command. Use
Command.andThen(Command...)
instead. -
getController
Returns the PIDController used by the command.- Returns:
- The PIDController
-