Class PivotToCmd<T extends TagalongSubsystemBase & PivotAugment>

All Implemented Interfaces:
Sendable

Command that moves the pivot absolutely to the desired position
  • Constructor Details

    • PivotToCmd

      public PivotToCmd(T pivot, Angle goalPosition)
      Constructor with default to hold position after
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot position
    • PivotToCmd

      public PivotToCmd(int id, T pivot, Angle goalPosition)
      Constructor with default to hold position after
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
    • PivotToCmd

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

      public PivotToCmd(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 - Goal pivot positon
      holdPositionAfter - If the pivot should hold position when the command completes
    • PivotToCmd

      public PivotToCmd(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 - Goal pivot positon
      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
    • PivotToCmd

      public PivotToCmd(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 - Goal pivot positon
      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
    • PivotToCmd

      public PivotToCmd(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 - Goal pivot positon
      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 short of or beyond the target position the pivot can be while still being considered in tolerance
    • PivotToCmd

      public PivotToCmd(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 - Goal pivot positon
      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 short of or beyond the target position the pivot can be while still being considered in tolerance
    • PivotToCmd

      public PivotToCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
      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 short of 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
    • PivotToCmd

      public PivotToCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
      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 short of 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
    • PivotToCmd

      public PivotToCmd(T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Constructor that creates the command with the below parameters.
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
      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 short of the target position the pivot can be while still being considered in tolerance
      requiredInToleranceDurationS - The number of seconds that being in tolerance is required for
    • PivotToCmd

      public PivotToCmd(int id, T pivot, Angle goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - The pivot integer ID
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
      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 short of 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 number of seconds that being in tolerance is required for
    • PivotToCmd

      public PivotToCmd(T pivot, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor, allows for double for goal in rare cases of advance use needing a direct way to interact
      Parameters:
      pivot - Tagalong Subsystem containing a pivot microsystem
      goalPosition - Goal pivot positon
      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 short of 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 number of seconds that being in tolerance is required for
    • PivotToCmd

      public PivotToCmd(int id, T pivot, double goalPosition, boolean holdPositionAfter, double maxVelocityRPS, double lowerToleranceRot, double upperToleranceRot, double requiredInToleranceDurationS)
      Full constructor, allows for double for goal 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
      goalPosition - Goal pivot positon
      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 short of 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 number of seconds that being in tolerance is required for
  • Method Details