Package edu.wpi.first.wpilibj2.command
Class PIDCommand
- java.lang.Object
-
- edu.wpi.first.wpilibj2.command.CommandBase
-
- edu.wpi.first.wpilibj2.command.PIDCommand
-
public class PIDCommand extends CommandBase
A command that controls an output with aPIDController
. 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.
-
-
Field Summary
Fields Modifier and Type Field Description protected PIDController
m_controller
protected DoubleSupplier
m_measurement
protected DoubleSupplier
m_setpoint
protected DoubleConsumer
m_useOutput
-
Fields inherited from class edu.wpi.first.wpilibj2.command.CommandBase
m_requirements
-
-
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
All Methods Instance Methods Concrete Methods 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.CommandBase
addRequirements, getName, getRequirements, getSubsystem, initSendable, setName, setSubsystem, withName
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj2.command.Command
alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineWith, hasRequirement, isFinished, isScheduled, perpetually, raceWith, runsWhenDisabled, schedule, schedule, withInterrupt, withTimeout
-
-
-
-
Field Detail
-
m_controller
protected final PIDController m_controller
-
m_measurement
protected DoubleSupplier m_measurement
-
m_setpoint
protected DoubleSupplier m_setpoint
-
m_useOutput
protected DoubleConsumer m_useOutput
-
-
Constructor Detail
-
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 Detail
-
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.Do not schedule commands here that share requirements with this command. Use
Command.andThen(Command...)
instead.- Parameters:
interrupted
- whether the command was interrupted/canceled
-
getController
public PIDController getController()
Returns the PIDController used by the command.- Returns:
- The PIDController
-
-