Package tagalong.commands.base
Class RollToCmd<T extends TagalongSubsystemBase & RollerAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.RollToCmd<T>
- All Implemented Interfaces:
Sendable
Command that moves the roller absolutely to the desired position
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorsConstructorDescriptionRollToCmd
(int id, T roller, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Full constructor, allows for double for goal in rare cases of advance use needing a direct way to interactConstructor with default to hold position afterConstructor that creates the command with the below parameters.Constructor that creates the command with the below parameters.RollToCmd
(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot) Constructor that creates the command with the below parameters.RollToCmd
(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot) Constructor that creates the command with the below parameters.RollToCmd
(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Constructor that creates the command with the below parameters.RollToCmd
(T roller, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Full constructor, allows for double for goal in rare cases of advance use needing a direct way to interactConstructor with default to hold position afterConstructor that creates the command with the below parameters.Constructor that creates the command with the below parameters.RollToCmd
(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot) Constructor that creates the command with the below parameters.RollToCmd
(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot) Constructor that creates the command with the below parameters.RollToCmd
(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Constructor that creates the command with the below parameters. -
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
-
RollToCmd
Constructor with default to hold position after- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller position
-
RollToCmd
Constructor with default to hold position after- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller position
-
RollToCmd
Constructor that creates the command with the below parameters.- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completes
-
RollToCmd
Constructor that creates the command with the below parameters.- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completes
-
RollToCmd
Constructor that creates the command with the below parameters.- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this command
-
RollToCmd
public RollToCmd(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this command
-
RollToCmd
public RollToCmd(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot) Constructor that creates the command with the below parameters.- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandtoleranceRot
- The number of rotations short of or beyond the target position the roller can be while still being considered in tolerance
-
RollToCmd
public RollToCmd(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot) Constructor that creates the command with the below parameters.- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandtoleranceRot
- The number of rotations short of or beyond the target position the roller can be while still being considered in tolerance
-
RollToCmd
public RollToCmd(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot) Constructor that creates the command with the below parameters.- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandlowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in toleranceupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerance
-
RollToCmd
public RollToCmd(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot) Constructor that creates the command with the below parameters.- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandlowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in toleranceupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerance
-
RollToCmd
public RollToCmd(T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Constructor that creates the command with the below parameters.- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerancelowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in tolerancerequiredInToleranceDurationS
- The number of seconds that being in tolerance is required for
-
RollToCmd
public RollToCmd(int id, T roller, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Constructor that creates the command with the below parameters.- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandlowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in toleranceupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerancerequiredInToleranceDurationS
- The number of seconds that being in tolerance is required for
-
RollToCmd
public RollToCmd(T roller, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Full constructor, allows for double for goal in rare cases of advance use needing a direct way to interact- Parameters:
roller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandlowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in toleranceupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerancerequiredInToleranceDurationS
- The number of seconds that being in tolerance is required for
-
RollToCmd
public RollToCmd(int id, T roller, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS) Full constructor, allows for double for goal in rare cases of advance use needing a direct way to interact- Parameters:
id
- The roller integer IDroller
- Tagalong Subsystem containing a roller microsystemgoalPosition
- Goal roller positionholdPositionAfter
- If the roller should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the roller, in rotations per second, during this commandlowerToleranceRot
- The number of rotations short of the target position the roller can be while still being considered in toleranceupperToleranceRot
- The number of rotations beyond the target position the roller can be while still being considered in tolerancerequiredInToleranceDurationS
- The number of seconds that being in tolerance is required for
-
-
Method Details
-
initialize
- Overrides:
initialize
in classCommand
-
execute
-
end
-
isFinished
- Overrides:
isFinished
in classCommand
-