Package tagalong.commands.base
Class PivotToDynamicCmd<T extends TagalongSubsystemBase & PivotAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.PivotToDynamicCmd<T>
- All Implemented Interfaces:
Sendable
- Direct Known Subclasses:
PivotAimAtCmd
,PivotAimAtYawCompCmd
public class PivotToDynamicCmd<T extends TagalongSubsystemBase & PivotAugment>
extends TagalongCommand
Command that continuously moves the pivot to the goal supplier's target position
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorsConstructorDescriptionPivotToDynamicCmd
(int id, T pivot, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.PivotToDynamicCmd
(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.PivotToDynamicCmd
(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position.PivotToDynamicCmd
(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) Continuously move to the double suppliers target position.PivotToDynamicCmd
(T pivot, DoubleSupplier goalSupplierRot) Continuously move to the double suppliers target position.PivotToDynamicCmd
(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter) Continuously move to the double suppliers target position.PivotToDynamicCmd
(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS) Continuously move to the double suppliers target position.PivotToDynamicCmd
(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) 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
-
PivotToDynamicCmd
public PivotToDynamicCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) 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 pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the pivot during this commandstartSupplier
- BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
-
PivotToDynamicCmd
public PivotToDynamicCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier) 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:
pivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the pivot during this commandstartSupplier
- BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
-
PivotToDynamicCmd
public PivotToDynamicCmd(int id, T pivot, 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 pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the pivot during this command
-
PivotToDynamicCmd
public PivotToDynamicCmd(T pivot, 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:
pivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- Maximum velocity for the pivot during this command
-
PivotToDynamicCmd
public PivotToDynamicCmd(int id, T pivot, 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 pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completes
-
PivotToDynamicCmd
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:
pivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotationholdPositionAfter
- If the pivot should hold position when the command completes command
-
PivotToDynamicCmd
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 pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotation
-
PivotToDynamicCmd
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:
pivot
- Tagalong Subsystem containing an pivot microsystemgoalSupplierRot
- DoubleSupplier for the pivot rotation
-
-
Method Details
-
initialize
- Overrides:
initialize
in classCommand
-
execute
-
end
-
isFinished
- Overrides:
isFinished
in classCommand
-