Package tagalong.commands.base
Class RollToDynamicCmd<T extends TagalongSubsystemBase & RollerAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.RollToDynamicCmd<T>
- All Implemented Interfaces:
Sendable
- Direct Known Subclasses:
RollerAimAtCmd
,RollerAimAtYawCompCmd
public class RollToDynamicCmd<T extends TagalongSubsystemBase & RollerAugment>
extends TagalongCommand
Command for the roller to continuously move towards the goal supplier's target height
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorsConstructorDescriptionRollToDynamicCmd
(int id, T roller, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.RollToDynamicCmd
(int id, T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.RollToDynamicCmd
(int id, T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position.RollToDynamicCmd
(T roller, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.RollToDynamicCmd
(T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.RollToDynamicCmd
(T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position. -
Method Summary
Methods inherited from class tagalong.commands.TagalongCommand
anonymize
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
-
RollToDynamicCmd
public RollToDynamicCmd(int id, T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
id
- Integer ID of the roller microsystem inside the Tagalong Subsystemroller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller heightholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the roller during this command
-
RollToDynamicCmd
public RollToDynamicCmd(T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
roller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller heightholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the roller during this command
-
RollToDynamicCmd
public RollToDynamicCmd(int id, T roller, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
id
- Integer ID of the roller microsystem inside the Tagalong Subsystemroller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller heightholdPositionAfter
- If the roller should hold position when the command completes
-
RollToDynamicCmd
Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
roller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller heightholdPositionAfter
- If the roller should hold position when the command completes command
-
RollToDynamicCmd
Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
id
- Integer ID of the roller microsystem inside the Tagalong Subsystemroller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller height
-
RollToDynamicCmd
Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.- Parameters:
roller
- Tagalong Subsystem containing an roller microsystemgoalSupplierRot
- DoubleSupplier for the roller height
-
-
Method Details
-
initialize
- Overrides:
initialize
in classCommand
-
execute
-
end
-
isFinished
- Overrides:
isFinished
in classCommand
-