001/**
002 * Copyright 2024 The Space Cookies : Girl Scout Troop #62868 and FRC Team #1868
003 * Open Source Software; you may modify and/or share it under the terms of
004 * the 3-Clause BSD License found in the root directory of this project.
005 */
006
007package tagalong.subsystems.micro.confs;
008
009import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
010import com.ctre.phoenix6.signals.InvertedValue;
011import com.ctre.phoenix6.signals.NeutralModeValue;
012import edu.wpi.first.math.controller.SimpleMotorFeedforward;
013import edu.wpi.first.wpilibj.IterativeRobotBase;
014import tagalong.controls.FeedforwardConstants;
015import tagalong.controls.PIDSGVAConstants;
016import tagalong.devices.Motors;
017import tagalong.units.AccelerationUnits;
018import tagalong.units.DistanceUnits;
019import tagalong.units.VelocityUnits;
020
021/**
022 * Configuration for the roller microsystem
023 */
024public class RollerConf extends MicrosystemConf {
025  /**
026   * Dimension of the mechanical system
027   */
028  public final double mech2dDim;
029  /**
030   * Sim root name
031   */
032  public final String rootName;
033  /**
034   * Sim root x coordinate
035   */
036  public final double rootX;
037  /**
038   * Sim root y coordinate
039   */
040  public final double rootY;
041  /**
042   * Number of simulated ligaments used
043   */
044  public final int simNumLigaments;
045  /**
046   * Moment of inertia for the roller
047   */
048  public final double rollerMOI;
049  /**
050   * Motor feedforward model
051   */
052  public final SimpleMotorFeedforward feedForward;
053
054  /**
055   *
056   * @param name                          name of the subsystem
057   * @param motorTypes                    array of motor types used
058   * @param motorDeviceIDs                CAN IDs of the motors
059   * @param motorCanBus                   CAN buses which the motors are connected to
060   * @param motorDirection                motor inversion settings
061   * @param motorEnabledBrakeMode         brake mode when motors are enabled
062   * @param motorDisabledBrakeMode        brake mode when motors are disabled
063   * @param gearRatio                     gear ratios
064   * @param trapezoidalLengthUnit         units for trapezoidal motion length
065   * @param trapezoidalVelocityUnit       units for trapezoidal motion velocity
066   * @param trapezoidalLimitsVelocity     velocity limits for trapezoidal motion
067   * @param trapezoidalAccelerationUnit   units for trapezoidal motion acceleration
068   * @param trapezoidalLimitsAcceleration acceleration limits for trapezoidal motion
069   * @param defaultTolerancesUnit         default unit of the tolerance values
070   * @param defaultLowerTolerance         default lower tolerance
071   * @param defaultUpperTolerance         default upper tolerance
072   * @param feedForward                   feedforward constants
073   * @param simFeedForward                simulated feedforward constants
074   * @param currentLimitsConfigs          current limit configurations
075   * @param slot0                         PID slot 0 configuration
076   * @param slot1                         PID slot 1 configuration
077   * @param slot2                         PID slot 2 configuration
078   * @param simSlot0                      simulated PID slot 0 configuration
079   * @param simSlot1                      simulated PID slot 1 configuration
080   * @param simSlot2                      simulated PID slot 2 configuration
081   * @param mech2dDim                     dimensions of mechanical system
082   * @param rootName                      sim root name
083   * @param rootX                         sim root x coordinate
084   * @param rootY                         sim root y coordinate
085   * @param simNumLigaments               number of simulated ligaments used
086   * @param rollerMOI                     moment of inertia for the roller
087   */
088  public RollerConf(
089      String name,
090      Motors[] motorTypes,
091      int[] motorDeviceIDs,
092      String[] motorCanBus,
093      InvertedValue[] motorDirection,
094      NeutralModeValue[] motorEnabledBrakeMode,
095      NeutralModeValue[] motorDisabledBrakeMode,
096      int[][] gearRatio,
097      DistanceUnits trapezoidalLengthUnit,
098      VelocityUnits trapezoidalVelocityUnit,
099      double trapezoidalLimitsVelocity,
100      AccelerationUnits trapezoidalAccelerationUnit,
101      double trapezoidalLimitsAcceleration,
102      DistanceUnits defaultTolerancesUnit,
103      double defaultLowerTolerance,
104      double defaultUpperTolerance,
105      FeedforwardConstants feedForward,
106      FeedforwardConstants simFeedForward,
107      CurrentLimitsConfigs currentLimitsConfigs,
108      PIDSGVAConstants slot0,
109      PIDSGVAConstants slot1,
110      PIDSGVAConstants slot2,
111      PIDSGVAConstants simSlot0,
112      PIDSGVAConstants simSlot1,
113      PIDSGVAConstants simSlot2,
114      double mech2dDim,
115      String rootName,
116      double rootX,
117      double rootY,
118      int simNumLigaments,
119      double rollerMOI
120  ) {
121    super(
122        name,
123        motorTypes,
124        motorDeviceIDs,
125        motorCanBus,
126        motorDirection,
127        motorEnabledBrakeMode,
128        motorDisabledBrakeMode,
129        gearRatio,
130        trapezoidalLengthUnit,
131        VelocityUnits.ROTATIONS_PER_SECOND,
132        trapezoidalVelocityUnit.convertX(
133            trapezoidalLimitsVelocity, VelocityUnits.ROTATIONS_PER_SECOND
134        ),
135        AccelerationUnits.ROTATIONS_PER_SECOND2,
136        trapezoidalAccelerationUnit.convertX(
137            trapezoidalLimitsAcceleration, AccelerationUnits.ROTATIONS_PER_SECOND2
138        ),
139        DistanceUnits.ROTATION,
140        defaultTolerancesUnit.convertX(defaultLowerTolerance, DistanceUnits.ROTATION),
141        defaultTolerancesUnit.convertX(defaultUpperTolerance, DistanceUnits.ROTATION),
142        currentLimitsConfigs,
143        slot0,
144        slot1,
145        slot2,
146        simSlot0,
147        simSlot1,
148        simSlot2
149    );
150    this.mech2dDim = mech2dDim;
151    this.rootName = rootName;
152    this.rootX = rootX;
153    this.rootY = rootY;
154    this.simNumLigaments = simNumLigaments;
155    this.rollerMOI = rollerMOI;
156    this.feedForward = IterativeRobotBase.isReal() ? feedForward.getSimpleMotorFeedforward()
157                                                   : simFeedForward.getSimpleMotorFeedforward();
158  }
159}