Class RollToCmd<T extends TagalongSubsystemBase & RollerAugment>

All Implemented Interfaces:
Sendable

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

    • RollToCmd

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

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

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

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

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

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

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

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

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

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

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

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

      public RollToCmd(T roller, 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:
      roller - Tagalong Subsystem containing a roller microsystem
      goalPosition - Goal roller position
      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
      lowerToleranceRot - The number of rotations short of the target position the roller can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the roller can be while still being considered in tolerance
      requiredInToleranceDurationS - The number of seconds that being in tolerance is required for
    • RollToCmd

      public RollToCmd(int id, T roller, 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 roller integer ID
      roller - Tagalong Subsystem containing a roller microsystem
      goalPosition - Goal roller position
      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
      lowerToleranceRot - The number of rotations short of the target position the roller can be while still being considered in tolerance
      upperToleranceRot - The number of rotations beyond the target position the roller can be while still being considered in tolerance
      requiredInToleranceDurationS - The number of seconds that being in tolerance is required for
  • Method Details