Package edu.wpi.first.wpilibj2.command
Class TrapezoidProfileCommand
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand
- All Implemented Interfaces:
Sendable
Deprecated, for removal: This API element is subject to removal in a future version.
Use a TrapezoidProfile instead
A command that runs a
TrapezoidProfile. Useful for smoothly controlling mechanism motion.
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 -
Constructor Summary
ConstructorsConstructorDescriptionTrapezoidProfileCommand(TrapezoidProfile profile, Consumer<TrapezoidProfile.State> output, Supplier<TrapezoidProfile.State> goal, Supplier<TrapezoidProfile.State> currentState, Subsystem... requirements) Deprecated, for removal: This API element is subject to removal in a future version.Creates a new TrapezoidProfileCommand that will execute the givenTrapezoidProfile. -
Method Summary
Modifier and TypeMethodDescriptionvoidend(boolean interrupted) Deprecated, for removal: This API element is subject to removal in a future version.The action to take when the command ends.voidexecute()Deprecated, for removal: This API element is subject to removal in a future version.The main body of a command.voidDeprecated, for removal: This API element is subject to removal in a future version.The initial subroutine of a command.booleanDeprecated, for removal: This API element is subject to removal in a future version.Whether the command has finished.Methods inherited from class edu.wpi.first.wpilibj2.command.Command
addRequirements, addRequirements, alongWith, andThen, andThen, asProxy, beforeStarting, beforeStarting, cancel, deadlineFor, deadlineWith, finallyDo, finallyDo, getInterruptionBehavior, getName, getRequirements, getSubsystem, handleInterrupt, hasRequirement, ignoringDisable, initSendable, isScheduled, onlyIf, onlyWhile, raceWith, repeatedly, runsWhenDisabled, schedule, setName, setSubsystem, unless, until, withDeadline, withInterruptBehavior, withName, withTimeout, withTimeout
-
Constructor Details
-
TrapezoidProfileCommand
public TrapezoidProfileCommand(TrapezoidProfile profile, Consumer<TrapezoidProfile.State> output, Supplier<TrapezoidProfile.State> goal, Supplier<TrapezoidProfile.State> currentState, Subsystem... requirements) Deprecated, for removal: This API element is subject to removal in a future version.Creates a new TrapezoidProfileCommand that will execute the givenTrapezoidProfile. Output will be piped to the provided consumer function.- Parameters:
profile- The motion profile to execute.output- The consumer for the profile output.goal- The supplier for the desired statecurrentState- The current staterequirements- The subsystems required by this command.
-
-
Method Details
-
initialize
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from class:CommandThe initial subroutine of a command. Called once when the command is initially scheduled.- Overrides:
initializein classCommand
-
execute
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from class:CommandThe main body of a command. Called repeatedly while the command is scheduled. -
end
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from class:CommandThe 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. -
isFinished
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from class:CommandWhether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.- Overrides:
isFinishedin classCommand- Returns:
- whether the command has finished.
-