Package tagalong.commands.aim
Class PivotAimAtCmd<T extends TagalongSubsystemBase & PivotAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.PivotToDynamicCmd<T>
tagalong.commands.aim.PivotAimAtCmd<T>
- All Implemented Interfaces:
Sendable
public class PivotAimAtCmd<T extends TagalongSubsystemBase & PivotAugment>
extends PivotToDynamicCmd<T>
Command that continuously points at a target in 2d space.
For rotational targeting give robot position as (X, Y) pose
For vertical targets give (distance from target, mechanism height)
-
Nested Class Summary
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.Command
Command.InterruptionBehavior
-
Constructor Summary
ConstructorsConstructorDescriptionPivotAimAtCmd
(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target) Minimal constructor with default parametersPivotAimAtCmd
(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.PivotAimAtCmd
(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.PivotAimAtCmd
(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target) Minimal constructor with default parametersPivotAimAtCmd
(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.PivotAimAtCmd
(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters. -
Method Summary
Modifier and TypeMethodDescriptionprotected static DoubleSupplier
positionTransform
(Supplier<Translation2d> location, DoubleSupplier pivotPosition, Translation2d target, double pivotMinRot, double pivotMaxRot) Transform position into an optimal path angle to target, ignores yaw while respecting the system's positional limitsMethods inherited from class tagalong.commands.base.PivotToDynamicCmd
end, execute, initialize, isFinished
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
-
PivotAimAtCmd
public PivotAimAtCmd(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target) Minimal constructor with default parameters- Parameters:
id
- Integer ID of the pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target location
-
PivotAimAtCmd
Minimal constructor with default parameters- Parameters:
pivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target location
-
PivotAimAtCmd
public PivotAimAtCmd(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.- Parameters:
id
- Integer ID of the pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target locationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the pivot, in rotations per second, during this command
-
PivotAimAtCmd
public PivotAimAtCmd(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.- Parameters:
pivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target locationholdPositionAfter
- If the pivot should hold position when the command completesmaxVelocityRPS
- The maximum velocity of the pivot, in rotations per second, during this command
-
PivotAimAtCmd
public PivotAimAtCmd(int id, T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.- Parameters:
id
- Integer ID of the pivot microsystem inside the Tagalong Subsystempivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target locationholdPositionAfter
- If the pivot should hold position when the command completes
-
PivotAimAtCmd
public PivotAimAtCmd(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.- Parameters:
pivot
- Tagalong Subsystem containing a pivot microsystempositionSupplier
- Supplies the current robot position positiontarget
- Unmoving 2-dimensional target locationholdPositionAfter
- If the pivot should hold position when the command completes
-
-
Method Details
-
positionTransform
protected static DoubleSupplier positionTransform(Supplier<Translation2d> location, DoubleSupplier pivotPosition, Translation2d target, double pivotMinRot, double pivotMaxRot) Transform position into an optimal path angle to target, ignores yaw while respecting the system's positional limits- Parameters:
location
- Current robot location supplierpivotPosition
- Pivot position suppliertarget
- Target to aim at's locationpivotMinRot
- pivots minimum position in rotationspivotMaxRot
- pivots maximum position in rotations- Returns:
- Optimal path target angle for the pivot
-