Class Elevator

java.lang.Object
tagalong.subsystems.micro.Microsystem
tagalong.subsystems.micro.Elevator

public class Elevator extends Microsystem
Elevator Microsystem
  • Field Details

    • _elevatorConf

      Configuration for the elevator
    • _motorToMechRatio

      protected final double _motorToMechRatio
      Ratio between motor rotations and drum rotations
    • _elevatorMinHeightM

      public final double _elevatorMinHeightM
      Minimum height of the elevator in meters, Maximum height of the elevator in meters
    • _elevatorMaxHeightM

      public final double _elevatorMaxHeightM
      Minimum height of the elevator in meters, Maximum height of the elevator in meters
    • _maxVelocityMPS

      public final double _maxVelocityMPS
      Maximum velocity of the elevator in meters per second, Maximum acceleration of the elevator in meters per second squared
    • _maxAccelerationMPS2

      public final double _maxAccelerationMPS2
      Maximum velocity of the elevator in meters per second, Maximum acceleration of the elevator in meters per second squared
    • _defaultElevatorLowerToleranceM

      public final double _defaultElevatorLowerToleranceM
      Default lower tolerance of the elevator in meters, Default upper tolerance of the elevator in meters
    • _defaultElevatorUpperToleranceM

      public final double _defaultElevatorUpperToleranceM
      Default lower tolerance of the elevator in meters, Default upper tolerance of the elevator in meters
    • _elevatorZeroingPower

      public final double _elevatorZeroingPower
      Power for zeroing the elevator
    • _elevatorZeroingStallToleranceM

      public final double _elevatorZeroingStallToleranceM
      Positional tolerance in meters for zeroing the elevator
    • _elevatorZeroingDurationS

      public final double _elevatorZeroingDurationS
      Duration of stalling in seconds necessary for the elevator zero command to finish
    • _elevatorFF

      Feedforward model for the elevator
    • _elevatorSim

      Simulation for the elevator
    • _elevatorBaseStageLigament

      Base stage ligament
    • _elevatorStage1Ligament

      Stage 1 ligament
    • _simVelocityMPS

      protected double _simVelocityMPS
      Velocity of the simulated elevator in meters per second
    • _primaryMotorInverted

      protected boolean _primaryMotorInverted
      Whether or not the primary motor is inverted
  • Constructor Details

    • Elevator

      public Elevator(ElevatorConf conf)
      Constructs an elevator microsystem with the below configurations
      Parameters:
      conf - Configuration for the elevator
  • Method Details

    • configAllDevices

      public void configAllDevices()
      Description copied from class: Microsystem
      Configures devices
      Overrides:
      configAllDevices in class Microsystem
    • followLastProfile

      public void followLastProfile()
      Calculates the next state according to the trapezoidal profile and requests the elevator motor(s) to arrive at the next position with feedforward
    • setElevatorProfile

      public void setElevatorProfile(Height goalPosition)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPosition - goal position in meters
    • setElevatorProfile

      public void setElevatorProfile(Height goalPosition, double goalVelocityMPS)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPosition - goal position in meters
      goalVelocityMPS - goal velocity in meters per second
    • setElevatorProfile

      public void setElevatorProfile(Height goalPosition, double goalVelocityMPS, double maxVelocityMPS)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPosition - goal position in meters
      goalVelocityMPS - goal velocity in meters per second
      maxVelocityMPS - maximum velocity in meters per second
    • setElevatorProfile

      public void setElevatorProfile(Height goalPosition, double goalVelocityMPS, double maxVelocityMPS, double maxAccelerationMPS2)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPosition - goal position in meters
      goalVelocityMPS - goal velocity in meters per second
      maxVelocityMPS - maximum velocity in meters per second
      maxAccelerationMPS2 - maximum acceleration in meters per second squared
    • setElevatorProfile

      public void setElevatorProfile(Height goalPosition, double goalVelocityMPS, double maxVelocityMPS, double maxAccelerationMPS2, boolean setCurrentState)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPosition - goal position in meters
      goalVelocityMPS - goal velocity in meters per second
      maxVelocityMPS - maximum velocity in meters per second
      maxAccelerationMPS2 - maximum acceleration in meters per second squared
      setCurrentState - True if the profiles current state should base itself off sensor values rather than continue from the existing state
    • setElevatorProfile

      public void setElevatorProfile(double goalPositionM)
      Creates a new trapezoidal profile for the elevator to follow
      Parameters:
      goalPositionM - goal position in meters
    • setElevatorProfile

      public void setElevatorProfile(double goalPositionM, double goalVelocityMPS)
      Creates a new trapezoidal profile for the elevator
      Parameters:
      goalPositionM - The goal position to reach, in meters
      goalVelocityMPS - The goal velocity to reach, in meters per second
    • setElevatorProfile

      public void setElevatorProfile(double goalPositionM, double goalVelocityMPS, double maxVelocityMPS)
      Creates a new trapezoidal profile for the elevator
      Parameters:
      goalPositionM - The goal position to reach, in meters
      goalVelocityMPS - The goal velocity to reach, in meters per second
      maxVelocityMPS - The maximum velocity, in meters per second
    • setElevatorProfile

      public void setElevatorProfile(double goalPositionM, double goalVelocityMPS, double maxVelocityMPS, double maxAccelerationMPS2)
      Creates a new trapezoidal profile for the elevator
      Parameters:
      goalPositionM - The goal position to reach, in meters
      goalVelocityMPS - The goal velocity to reach, in meters per second
      maxVelocityMPS - The maximum velocity, in meters per second
      maxAccelerationMPS2 - The maximum acceleration, in meters per second squared
    • setElevatorProfile

      public void setElevatorProfile(double goalPositionM, double goalVelocityMPS, double maxVelocityMPS, double maxAccelerationMPS2, boolean setCurrentState)
      Creates a new trapezoidal profile for the elevator
      Parameters:
      goalPositionM - The goal position to reach, in meters
      goalVelocityMPS - The goal velocity to reach, in meters per second
      maxVelocityMPS - The maximum velocity, in meters per second
      maxAccelerationMPS2 - The maximum acceleration, in meters per second squared
      setCurrentState - True if the profiles current state should base itself off sensor values rather than continue from the existing state
    • getElevatorHeightM

      public double getElevatorHeightM()
      Gets the height of the elevator in meters
      Returns:
      height in meters
    • getElevatorVelocityMPS

      public double getElevatorVelocityMPS()
      Gets the velocity of the elevator in meters per second
      Returns:
      velocity in meters per second
    • setElevatorVelocity

      public void setElevatorVelocity(double mps, boolean withFF)
      Sets the velocity of the elevator in MPS
      Parameters:
      mps - Desired velocity in meters per second
      withFF - with feedforward
    • clampElevatorPosition

      public double clampElevatorPosition(double target)
      Clamps the elevator position to be within height limits
      Parameters:
      target - goal position of the elevator in meters
      Returns:
      clamped goal position in meters
    • onEnable

      public void onEnable()
      Description copied from class: Microsystem
      Sets break mode for all motors If system is in PID tuning mode is updates all PID related settings If the system is in Feedforward Tuning mode, it sets the primary motor to coast mode.
      Overrides:
      onEnable in class Microsystem
    • onDisable

      public void onDisable()
      Description copied from class: Microsystem
      returns nothing if micro system is disabled
      Overrides:
      onDisable in class Microsystem
    • periodic

      public void periodic()
      Description copied from class: Microsystem
      Periodic update function
      Overrides:
      periodic in class Microsystem
    • simulationInit

      public void simulationInit()
      Description copied from class: Microsystem
      Initializes simulation
      Overrides:
      simulationInit in class Microsystem
    • simulationPeriodic

      public void simulationPeriodic()
      Description copied from class: Microsystem
      Periodic function during simulation
      Overrides:
      simulationPeriodic in class Microsystem
    • updateShuffleboard

      public void updateShuffleboard()
      Description copied from class: Microsystem
      Updates shuffleboard
      Overrides:
      updateShuffleboard in class Microsystem
    • configShuffleboard

      public void configShuffleboard()
      Configure shuffleboard for the elevator
      Overrides:
      configShuffleboard in class Microsystem
    • motorToMeters

      public double motorToMeters(double rotation)
      Converts motor rotations to elevator height
      Parameters:
      rotation - motor position in rotations
      Returns:
      elevator position in meters
    • metersToMotor

      public double metersToMotor(double meter)
      Converts elevator height to motor rotations
      Parameters:
      meter - elevator position in meters
      Returns:
      motor position in rotations
    • isSafeToMove

      public boolean isSafeToMove()
      Checks whether or not it's safe for the elevator to move
      Returns:
      whether or not it's safe to move
    • isElevatorInTolerance

      public boolean isElevatorInTolerance(double lowerBound, double upperBound)
      Bounds checking function that uses the current elevator position
      Parameters:
      lowerBound - minimum of acceptable range
      upperBound - maximum of acceptable range
      Returns:
      if the current position is in specified acceptable range
    • setElevatorHeight

      public void setElevatorHeight(double height)
      Sets the position of the elevator in meters
      Parameters:
      height - goal position in meters
    • holdCurrentPosition

      public void holdCurrentPosition()
      Description copied from class: Microsystem
      Sets the power of the primary motor to zero
      Overrides:
      holdCurrentPosition in class Microsystem
    • getElevatorBaseStageLigament

      Retrieves base stage ligament attached to elevator Mechanism2d
      Returns:
      elevator base stage ligament
    • getElevatorStage1Ligament

      Retrieves stage 1 ligament attached to elevator Mechanism2d
      Returns:
      elevator stage 1 ligament