|
17 | 17 | import com.revrobotics.CANSparkMaxLowLevel; |
18 | 18 | import com.revrobotics.SparkMaxPIDController; |
19 | 19 |
|
20 | | -import org.carlmontrobotics.lib199.MotorErrors.TemperatureLimit; |
| 20 | +import org.carlmontrobotics.MotorConfig; |
21 | 21 | import org.carlmontrobotics.lib199.sim.MockSparkMax; |
22 | 22 | import org.carlmontrobotics.lib199.sim.MockTalonSRX; |
23 | 23 | import org.carlmontrobotics.lib199.sim.MockVictorSPX; |
@@ -78,10 +78,12 @@ public static WPI_TalonSRX createTalon(int id) { |
78 | 78 |
|
79 | 79 | //checks for spark max errors |
80 | 80 |
|
81 | | - public static CANSparkMax createSparkMax(int id, TemperatureLimit temperatureLimit) { |
| 81 | + @Deprecated |
| 82 | + public static CANSparkMax createSparkMax(int id, MotorErrors.TemperatureLimit temperatureLimit) { |
82 | 83 | return createSparkMax(id, temperatureLimit.limit); |
83 | 84 | } |
84 | 85 |
|
| 86 | + @Deprecated |
85 | 87 | public static CANSparkMax createSparkMax(int id, int temperatureLimit) { |
86 | 88 | CANSparkMax spark; |
87 | 89 | if (RobotBase.isReal()) { |
@@ -115,6 +117,39 @@ public static CANSparkMax createSparkMax(int id, int temperatureLimit) { |
115 | 117 | return spark; |
116 | 118 | } |
117 | 119 |
|
| 120 | + public static CANSparkMax createSparkMax(int id, MotorConfig config) { |
| 121 | + CANSparkMax spark; |
| 122 | + if (RobotBase.isReal()) { |
| 123 | + spark = new CachedSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless); |
| 124 | + if (spark.getFirmwareVersion() == 0) { |
| 125 | + spark.close(); |
| 126 | + System.err.println("SparkMax on port: " + id + " is not connected!"); |
| 127 | + return MotorErrors.createDummySparkMax(); |
| 128 | + } |
| 129 | + } else { |
| 130 | + spark = MockSparkMax.createMockSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless); |
| 131 | + } |
| 132 | + |
| 133 | + MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimit); |
| 134 | + |
| 135 | + MotorErrors.reportError(spark.restoreFactoryDefaults()); |
| 136 | + MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0)); |
| 137 | + MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake)); |
| 138 | + MotorErrors.reportError(spark.enableVoltageCompensation(12)); |
| 139 | + MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimit)); |
| 140 | + |
| 141 | + MotorErrors.checkSparkMaxErrors(spark); |
| 142 | + |
| 143 | + SparkMaxPIDController controller = spark.getPIDController(); |
| 144 | + MotorErrors.reportError(controller.setOutputRange(-1, 1)); |
| 145 | + MotorErrors.reportError(controller.setP(0)); |
| 146 | + MotorErrors.reportError(controller.setI(0)); |
| 147 | + MotorErrors.reportError(controller.setD(0)); |
| 148 | + MotorErrors.reportError(controller.setFF(0)); |
| 149 | + |
| 150 | + return spark; |
| 151 | + } |
| 152 | + |
118 | 153 | public static CANCoder createCANCoder(int port) { |
119 | 154 | CANCoder canCoder = new CANCoder(port); |
120 | 155 | if(RobotBase.isSimulation()) new MockedCANCoder(canCoder); |
|
0 commit comments