Package tagalong.commands.aim
Class RollerAimAtYawCompCmd<T extends TagalongSubsystemBase & RollerAugment>
java.lang.Object
edu.wpi.first.wpilibj2.command.Command
tagalong.commands.TagalongCommand
tagalong.commands.base.RollToDynamicCmd<T>
tagalong.commands.aim.RollerAimAtYawCompCmd<T>
- All Implemented Interfaces:
- Sendable
public class RollerAimAtYawCompCmd<T extends TagalongSubsystemBase & RollerAugment>
extends RollToDynamicCmd<T>
Command that continuously points at a target in 2d space while compensating for the current
 rotation of the robot. Since this is strictly rotational targeting give robot position as (X, Y)
 pose
- 
Nested Class SummaryNested classes/interfaces inherited from class edu.wpi.first.wpilibj2.command.CommandCommand.InterruptionBehavior
- 
Constructor SummaryConstructorsConstructorDescriptionRollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target) Minimal constructor with default parametersRollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.RollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.RollerAimAtYawCompCmd(T roller, Supplier<Pose2d> positionSupplier, Translation2d target) Minimal constructor with default parametersRollerAimAtYawCompCmd(T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.RollerAimAtYawCompCmd(T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.
- 
Method SummaryModifier and TypeMethodDescriptionprotected static DoubleSupplierpositionTransform(Supplier<Pose2d> location, DoubleSupplier rollerPosition, Translation2d target) Transform position into an optimal path angle to target, ignores yawMethods inherited from class tagalong.commands.base.RollToDynamicCmdend, execute, initialize, isFinishedMethods inherited from class tagalong.commands.TagalongCommandanonymizeMethods inherited from class edu.wpi.first.wpilibj2.command.CommandaddRequirements, 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- 
RollerAimAtYawCompCmdpublic RollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target) Minimal constructor with default parameters- Parameters:
- id- Integer ID of the roller microsystem inside the Tagalong Subsystem
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
 
- 
RollerAimAtYawCompCmdMinimal constructor with default parameters- Parameters:
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
 
- 
RollerAimAtYawCompCmdpublic RollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.- Parameters:
- id- Integer ID of the roller microsystem inside the Tagalong Subsystem
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
- holdPositionAfter- If the roller should hold position when the command completes
- maxVelocityRPS- The maximum velocity of the roller, in rotations per second, during this command
 
- 
RollerAimAtYawCompCmdpublic RollerAimAtYawCompCmd(T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter, double maxVelocityRPS) Constructor that creates the command with the below parameters.- Parameters:
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
- holdPositionAfter- If the roller should hold position when the command completes
- maxVelocityRPS- The maximum velocity of the roller, in rotations per second, during this command
 
- 
RollerAimAtYawCompCmdpublic RollerAimAtYawCompCmd(int id, T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.- Parameters:
- id- Integer ID of the roller microsystem inside the Tagalong Subsystem
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
- holdPositionAfter- If the roller should hold position when the command completes
 
- 
RollerAimAtYawCompCmdpublic RollerAimAtYawCompCmd(T roller, Supplier<Pose2d> positionSupplier, Translation2d target, boolean holdPositionAfter) Constructor that creates the command with the below parameters.- Parameters:
- roller- Tagalong Subsystem containing a roller microsystem
- positionSupplier- Supplies the current robot position position
- target- Unmoving 2-dimensional target location
- holdPositionAfter- If the roller should hold position when the command completes
 
 
- 
- 
Method Details- 
positionTransformprotected static DoubleSupplier positionTransform(Supplier<Pose2d> location, DoubleSupplier rollerPosition, Translation2d target) Transform position into an optimal path angle to target, ignores yaw- Parameters:
- location- Current robot location supplier
- rollerPosition- Roller position supplier
- target- Target to aim at's location
- Returns:
- Optimal path target angle for the roller
 
 
-