Class ElevatorConf

java.lang.Object
tagalong.subsystems.micro.confs.MicrosystemConf
tagalong.subsystems.micro.confs.ElevatorConf

public class ElevatorConf extends MicrosystemConf
Configuration for the elevator microsystem
  • Field Details

  • Constructor Details

    • ElevatorConf

      public ElevatorConf(String name, Motors[] motorTypes, int[] motorDeviceIDs, String[] motorCanBus, com.ctre.phoenix6.signals.InvertedValue[] motorDirection, com.ctre.phoenix6.signals.NeutralModeValue[] motorEnabledBrakeMode, com.ctre.phoenix6.signals.NeutralModeValue[] motorDisabledBrakeMode, int[][] gearRatio, DistanceUnits positionalLimitsUnit, double positionalMin, double positionalMax, DistanceUnits trapezoidalLengthUnit, VelocityUnits trapezoidalVelocityUnit, double trapezoidalLimitsVelocity, AccelerationUnits trapezoidalAccelerationUnit, double trapezoidalLimitsAcceleration, DistanceUnits defaultTolerancesUnit, double defaultLowerTolerance, double defaultUpperTolerance, FeedforwardConstants feedForward, FeedforwardConstants simFeedForward, com.ctre.phoenix6.configs.CurrentLimitsConfigs currentLimitsConfigs, PIDSGVAConstants slot0, PIDSGVAConstants slot1, PIDSGVAConstants slot2, MassUnits carriageMassUnit, double carriageMassValue, double mech2dDim, String rootName, double rootX, double rootY, double lineLength, double angle, PIDSGVAConstants simSlot0, PIDSGVAConstants simSlot1, PIDSGVAConstants simSlot2, DistanceUnits drumDiameterUnit, double drumDiameter)
      Parameters:
      name - name of the subsystem
      motorTypes - array of motor types used
      motorDeviceIDs - CAN IDs of the motors
      motorCanBus - CAN buses which the motors are connected to
      motorDirection - motor inversion settings
      motorEnabledBrakeMode - brake mode when motors are enabled
      motorDisabledBrakeMode - brake mode when motors are disabled
      gearRatio - gear ratios
      positionalLimitsUnit - units for positional limits on elevator
      positionalMin - positional minimum on elevator
      positionalMax - positional maximum on elevator
      trapezoidalLengthUnit - units for trapezoidal motion length
      trapezoidalVelocityUnit - units for trapezoidal motion velocityODO
      trapezoidalLimitsVelocity - velocity limits for trapezoidal motion
      trapezoidalAccelerationUnit - units for trapezoidal motion acceleration
      trapezoidalLimitsAcceleration - acceleration limits for trapezoidal motion
      defaultTolerancesUnit - default unit of the tolerance values
      defaultLowerTolerance - default lower tolerance
      defaultUpperTolerance - default upper tolerance
      feedForward - feedforward constants
      simFeedForward - simulated feedforward constants
      currentLimitsConfigs - current limit configurations
      slot0 - PID slot 0 configuration
      slot1 - PID slot 1 configuration
      slot2 - PID slot 2 configuration
      carriageMassUnit - units for the carriage mass
      carriageMassValue - value of the carriage mass
      mech2dDim - dimensions of mechanical system
      rootX - sim root x coordinate
      rootY - sim root y coordinate
      rootName - sim root name
      lineLength - length of the line
      angle - angle of the elevator
      simSlot0 - simulated PID slot 0 configuration
      simSlot1 - simulated PID slot 1 configuration
      simSlot2 - simulated PID slot 2 configuration
      drumDiameterUnit - units for the drum diameter
      drumDiameter - diameter of the drum