Class PivotToAbsoluteCmd<T extends TagalongSubsystemBase & PivotAugment>

All Implemented Interfaces:
Sendable

PivotToCommand with optimal pathing
  • Constructor Details

    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition, boolean holdPositionAfter)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      holdPositionAfter - If the pivot should hold position when the command completes
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      holdPositionAfter - If the pivot should hold position when the command completes
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      toleranceRot - The number of rotations below or beyond the target position the pivot can be while still being considered in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double toleranceRot)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      toleranceRot - The number of rotations below or beyond the target position the pivot can be while still being considered in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot)
      Constructor with no in tolerance duration requirement
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot)
      Constructor with ID for specifying pivot but no in tolerance duration requirement
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      requiredInToleranceDurationS - the duration (in seconds) the pivot must stay in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor with ID for specifying pivot
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - The goal position to reach
      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
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
      requiredInToleranceDurationS - the duration (in seconds) the pivot must stay in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(T pivot, double goalPositionRot, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor, allows for double for goal position (rotations) in rare cases of advance use needing a direct way to interact
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPositionRot - The goal position to reach, in rotations
      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
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
      requiredInToleranceDurationS - the duration (in seconds) the pivot must stay in tolerance
    • PivotToAbsoluteCmd

      public PivotToAbsoluteCmd(int id, T pivot, double goalPositionRot, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor, allows for double for goal position (rotations) in rare cases of advance use needing a direct way to interact
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPositionRot - The goal position to reach, in rotations
      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
      lowerToleranceRot - The number of rotations below the target position the pivot can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the pivot can be while still being considered in tolerance
      requiredInToleranceDurationS - the duration (in seconds) the pivot must stay in tolerance
  • Method Details