Class PivotConf

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

public class PivotConf extends MicrosystemConf
Configuration for the pivot microsystem
  • Field Details

  • Constructor Details

    • PivotConf

      public PivotConf(String name, Motors[] motorTypes, int[] motorDeviceIDs, String[] motorCanBus, com.ctre.phoenix6.signals.InvertedValue[] motorDirection, Encoders encoderType, int encoderDeviceID, String encoderCanBus, boolean encoderConfigZeroToOne, boolean encoderConfigClockwisePositive, DistanceUnits encoderConfigMagnetOffsetUnit, double encoderConfigMagnetOffsetValue, com.ctre.phoenix6.signals.NeutralModeValue[] motorEnabledBrakeMode, com.ctre.phoenix6.signals.NeutralModeValue[] motorDisabledBrakeMode, int[][] motorToPivotRatio, int[][] encoderToPivotRatio, DistanceUnits rotationalLimitsUnit, double rotationalMin, double rotationalMax, 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, PIDSGVAConstants simSlot0, PIDSGVAConstants simSlot1, PIDSGVAConstants simSlot2, boolean closedLoopConfigsContinuousWrap, DistanceUnits ffOffsetUnit, double ffOffsetValue, DistanceUnits profileOffsetUnit, double profileOffsetValue, double mech2dDim, String rootName, double rootX, double rootY, double pivotMOI, double pivotLengthM)
      Parameters:
      name - pivot name
      motorTypes - motor types
      motorDeviceIDs - motor device ids
      motorCanBus - motor can bus
      motorDirection - motor directions
      encoderType - encoder type used for the pivot
      encoderDeviceID - device id of the encoder
      encoderCanBus - can bus of the encoder
      encoderConfigZeroToOne - whether the encoder config operates in a 0 to 1 range
      encoderConfigClockwisePositive - whether the encoder is configured as clockwise positive
      encoderConfigMagnetOffsetUnit - unit of the encoder magnet offset
      encoderConfigMagnetOffsetValue - value of the encoder magnet offset
      motorEnabledBrakeMode - brake mode when motors are enabled
      motorDisabledBrakeMode - brake mode when motors are disabled
      motorToPivotRatio - ratio between the motor and encoder
      encoderToPivotRatio - gear ratio between encoder and pivot
      rotationalLimitsUnit - unit for rotational limit (default: rotations)
      rotationalMin - minimum rotation
      rotationalMax - maximum rotation
      trapezoidalLengthUnit - unit of trapezoidal motion length
      trapezoidalVelocityUnit - unit of trapezoidal velocity
      trapezoidalLimitsVelocity - trapezoidal motion velocity limits
      trapezoidalAccelerationUnit - unit of trapezoidal acceleration
      trapezoidalLimitsAcceleration - trapezoidal motion acceleration limits
      defaultTolerancesUnit - unit of default tolerances
      defaultLowerTolerance - default lower tolerance
      defaultUpperTolerance - default upper tolerance
      feedForward - feedforward model for the arm
      simFeedForward - feedforward model for simulation
      currentLimitsConfigs - current limit configurations
      slot0 - slot 0 configuration
      slot1 - slot 1 configuration
      slot2 - slot 2 configuration
      simSlot0 - slot 0 configuration for simulation
      simSlot1 - slot 1 configuration for simulation
      simSlot2 - slot 2 configuration for simulation
      closedLoopConfigsContinuousWrap - whether continuous wrapping in closed loop configs
      ffOffsetUnit - unit of the feedforward offset
      ffOffsetValue - value of the feedforward offset
      profileOffsetUnit - unit of the profile offset
      profileOffsetValue - value of the profile offset
      mech2dDim - dimensions of mechanical system
      rootName - sim root name
      rootX - sim root x coordinate
      rootY - sim root y coordinate
      pivotMOI - moment of inertia for the pivot
      pivotLengthM - length of the pivot in meters