Class ElevateToCmd<T extends TagalongSubsystemBase & ElevatorAugment>

All Implemented Interfaces:
Sendable

Base Command for linear system movement, moves system to specified height.
  • Constructor Details

    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPositionM)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPositionM)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPositionM, boolean holdPositionAfter)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPositionM, boolean holdPositionAfter)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double toleranceM)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      toleranceM - the desired tolerance for height, in meters
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double toleranceM)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      toleranceM - the desired tolerance for height, in meters
    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
    • ElevateToCmd

      public ElevateToCmd(T elevator, Height goalPosition, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM, double requiredInToleranceDurationS)
      Constructor that creates the command with the below parameters.
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPosition - The target height for the elevator
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
      requiredInToleranceDurationS - the duration (in seconds) the elevator must stay in tolerance
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, Height goalPosition, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM, double requiredInToleranceDurationS)
      Constructor that creates the command with the below parameters.
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPosition - The target height for the elevator
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
      requiredInToleranceDurationS - the duration (in seconds) the elevator must stay in tolerance
    • ElevateToCmd

      public ElevateToCmd(T elevator, double goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM, double requiredInToleranceDurationS)
      Full constructor, with the below parameters. Allows for double for goal in rare cases of advance use needing a direct way to interact
      Parameters:
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters, as a double
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
      requiredInToleranceDurationS - the duration (in seconds) the elevator must stay in tolerance
    • ElevateToCmd

      public ElevateToCmd(int id, T elevator, double goalPositionM, boolean holdPositionAfter, double maxVelocityMPS, double lowerToleranceM, double upperToleranceM, double requiredInToleranceDurationS)
      Full constructor, with the below parameters. Allows for double for goal in rare cases of advance use needing a direct way to interact
      Parameters:
      id - Integer ID of the elevator microsystem inside the Tagalong Subsystem
      elevator - Tagalong Subsystem containing an elevator microsystem
      goalPositionM - The target height for the elevator, in meters, as a double.
      holdPositionAfter - If the elevator should hold position when the command completes
      maxVelocityMPS - maximum velocity, in meters per second, the elevator can move
      lowerToleranceM - the lower bound for height tolerance, in meters
      upperToleranceM - the upper bound for height tolerance, in meters
      requiredInToleranceDurationS - the duration (in seconds) the elevator must stay in tolerance
  • Method Details