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.devices;
008
009import com.ctre.phoenix6.configs.TalonFXConfiguration;
010import com.ctre.phoenix6.signals.InvertedValue;
011import com.ctre.phoenix6.signals.NeutralModeValue;
012import edu.wpi.first.math.system.plant.DCMotor;
013import edu.wpi.first.wpilibj.IterativeRobotBase;
014import java.util.function.Function;
015import tagalong.units.VelocityUnits;
016
017/**
018 * Generic motor identifier enum
019 */
020public enum Motors implements CanDeviceInterface {
021  /**
022   * Kraken X60
023   */
024  KRAKEN_X60(6000, DCMotor::getKrakenX60),
025  /**
026   * Kraken X60 in FOC mode
027   */
028  KRAKEN_X60_FOC(5800, DCMotor::getKrakenX60Foc),
029  /**
030   * Falcon 500
031   */
032  FALCON500(6380, DCMotor::getFalcon500),
033  /**
034   * Falcon 500 in FOC mode
035   */
036  FALCON500_FOC(6080, DCMotor::getFalcon500),
037  /**
038   * Kraken X44
039   * FUTURE DEV: Waiting for motor specifications v2025
040   */
041  KRAKEN_X44(1, DCMotor::getKrakenX60),
042  /**
043   * Kraken X44 in FOC mode -- RPM WAITING FOR SPEC
044   * FUTURE DEV: Waiting for motor specifications v2025
045   */
046  KRAKEN_X44_FOC(1, DCMotor::getKrakenX60Foc);
047
048  /**
049   * Max free speed RPM and converted RPS of the motor
050   */
051  public final double maxRPM, maxRPS;
052  /**
053   * Motor's simulation supplier
054   */
055  public final Function<Integer, DCMotor> simSupplier;
056
057  /**
058   *
059   * @param maxRPM
060   */
061  Motors(double maxRPM, Function<Integer, DCMotor> simSupplier) {
062    this.maxRPM = maxRPM;
063    maxRPS =
064        VelocityUnits.ROTATIONS_PER_MINUTE.convertX(maxRPM, VelocityUnits.ROTATIONS_PER_SECOND);
065    this.simSupplier = simSupplier;
066  }
067
068  // FUTURE DEV: Make some defaults, especially current limits, specific to each motor
069  /**
070   * Default Stator and Supply current limits. We highly recommend that all
071   * Tagalong users configure these limits to the specific application
072   */
073  public static final double DEFAULT_STATOR_CURRENT_LIMIT_AMPS = 40.0,
074                             DEFAULT_SUPPLY_CURRENT_LIMIT_AMPS = 40.0,
075                             DEFAULT_SUPPLY_CURRENT_THRESHOLD_LIMIT_AMPS = 45.0,
076                             DEFAULT_SUPPLY_TIME_THRESHOLD = 0.1;
077
078  /**
079   *
080   * @return TalonFXConfiguration with Tagalong defaults
081   */
082  public static TalonFXConfiguration getDefaults() {
083    final TalonFXConfiguration config = new TalonFXConfiguration();
084
085    /* -------- Configurations that match CTRE Default configs -------- */
086    config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
087    config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
088    config.MotorOutput.DutyCycleNeutralDeadband = 0.0;
089
090    config.SoftwareLimitSwitch.ForwardSoftLimitEnable = false;
091    // config.SoftwareLimitSwitch.ForwardSoftLimitThreshold = 0;
092    config.SoftwareLimitSwitch.ReverseSoftLimitEnable = false;
093    // config.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0;
094
095    config.Voltage.SupplyVoltageTimeConstant = 0.0;
096    config.Voltage.PeakForwardVoltage = 16.0;
097    config.Voltage.PeakReverseVoltage = -16.0;
098
099    config.MotionMagic.MotionMagicCruiseVelocity = 0.0; // RPS
100    config.MotionMagic.MotionMagicAcceleration = 0.0; // RPS2
101    config.MotionMagic.MotionMagicJerk = 0.0; // RPS3
102
103    /* -------- 1868 Safe defaults that DO NOT match CTRE defaults -------- */
104    if (IterativeRobotBase.isReal()) {
105      // FUTURE DEV: Figure out why stator current limits break simulation.
106      config.CurrentLimits.StatorCurrentLimitEnable = true;
107      config.CurrentLimits.StatorCurrentLimit = DEFAULT_STATOR_CURRENT_LIMIT_AMPS;
108    }
109
110    config.CurrentLimits.SupplyCurrentLimitEnable = true;
111    config.CurrentLimits.SupplyCurrentLimit = DEFAULT_SUPPLY_CURRENT_LIMIT_AMPS;
112    config.CurrentLimits.SupplyCurrentLowerLimit = DEFAULT_SUPPLY_CURRENT_THRESHOLD_LIMIT_AMPS;
113    config.CurrentLimits.SupplyCurrentLowerTime = DEFAULT_SUPPLY_TIME_THRESHOLD; // seconds
114
115    config.TorqueCurrent.PeakForwardTorqueCurrent = DEFAULT_STATOR_CURRENT_LIMIT_AMPS;
116    config.TorqueCurrent.PeakReverseTorqueCurrent = -DEFAULT_STATOR_CURRENT_LIMIT_AMPS;
117    config.TorqueCurrent.TorqueNeutralDeadband = 0.0;
118
119    return config;
120  }
121}