Class PivotAimAtCmd<T extends TagalongSubsystemBase & PivotAugment>

All Implemented Interfaces:
Sendable

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)
  • 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 Subsystem
      pivot - Tagalong Subsystem containing a pivot microsystem
      positionSupplier - Supplies the current robot position position
      target - Unmoving 2-dimensional target location
    • PivotAimAtCmd

      public PivotAimAtCmd(T pivot, Supplier<Translation2d> positionSupplier, Translation2d target)
      Minimal constructor with default parameters
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      positionSupplier - Supplies the current robot position position
      target - 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 Subsystem
      pivot - Tagalong Subsystem containing a pivot microsystem
      positionSupplier - Supplies the current robot position position
      target - Unmoving 2-dimensional target location
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - 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 microsystem
      positionSupplier - Supplies the current robot position position
      target - Unmoving 2-dimensional target location
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - 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 Subsystem
      pivot - Tagalong Subsystem containing a pivot microsystem
      positionSupplier - Supplies the current robot position position
      target - Unmoving 2-dimensional target location
      holdPositionAfter - 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 microsystem
      positionSupplier - Supplies the current robot position position
      target - Unmoving 2-dimensional target location
      holdPositionAfter - 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 supplier
      pivotPosition - Pivot position supplier
      target - Target to aim at's location
      pivotMinRot - pivots minimum position in rotations
      pivotMaxRot - pivots maximum position in rotations
      Returns:
      Optimal path target angle for the pivot