Package edu.wpi.first.wpilibj2.command
Class ProfiledPIDCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.CommandBase
edu.wpi.first.wpilibj2.command.ProfiledPIDCommand
public class ProfiledPIDCommand extends CommandBase
A command that controls an output with a
ProfiledPIDController
. 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 ProfiledPIDController
m_controller
protected Supplier<TrapezoidProfile.State>
m_goal
protected DoubleSupplier
m_measurement
protected BiConsumer<Double,TrapezoidProfile.State>
m_useOutput
-
Constructor Summary
Constructors Constructor Description ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, double goal, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, TrapezoidProfile.State goal, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, DoubleSupplier goalSource, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController.ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, Supplier<TrapezoidProfile.State> goalSource, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)
Creates a new PIDCommand, which controls the given output with a ProfiledPIDController. -
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.ProfiledPIDController
getController()
Returns the ProfiledPIDController 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 Details
-
Constructor Details
-
ProfiledPIDCommand
public ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, Supplier<TrapezoidProfile.State> goalSource, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a ProfiledPIDController. Goal velocity is specified.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablegoalSource
- the controller's goaluseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
ProfiledPIDCommand
public ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, DoubleSupplier goalSource, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a ProfiledPIDController. Goal velocity is implicitly zero.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablegoalSource
- the controller's goaluseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
ProfiledPIDCommand
public ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, TrapezoidProfile.State goal, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a ProfiledPIDController. Goal velocity is specified.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablegoal
- the controller's goaluseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
ProfiledPIDCommand
public ProfiledPIDCommand(ProfiledPIDController controller, DoubleSupplier measurementSource, double goal, BiConsumer<Double,TrapezoidProfile.State> useOutput, Subsystem... requirements)Creates a new PIDCommand, which controls the given output with a ProfiledPIDController. Goal velocity is implicitly zero.- Parameters:
controller
- the controller that controls the output.measurementSource
- the measurement of the process variablegoal
- the controller's goaluseOutput
- the controller's outputrequirements
- the subsystems required by this command
-
-
Method Details
-
initialize
Description copied from interface:Command
The initial subroutine of a command. Called once when the command is initially scheduled. -
execute
Description copied from interface:Command
The main body of a command. Called repeatedly while the command is scheduled. -
end
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
Returns the ProfiledPIDController used by the command.- Returns:
- The ProfiledPIDController
-