Skip to content

Commit c24939a

Browse files
committed
resolved a few comments
1 parent a96b9c8 commit c24939a

File tree

3 files changed

+51
-23
lines changed

3 files changed

+51
-23
lines changed

src/main/java/org/carlmontrobotics/lib199/MotorControllerFactory.java

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,28 @@ public static SparkFlex createSparkFlex(int id, SparkBaseConfig config) {
157157
return spark;
158158
}
159159

160+
public static SparkBaseConfig createConfig(MotorControllerType type) {
161+
SparkBaseConfig config = null;
162+
switch(type){
163+
case SPARK_MAX:
164+
config = new SparkMaxConfig();
165+
break;
166+
case SPARK_FLEX:
167+
config = new SparkFlexConfig();
168+
break;
169+
}
170+
return config;
171+
}
172+
173+
public static MotorControllerType getControllerType(SparkBase motor){
174+
if(motor instanceof SparkMax){
175+
return MotorControllerType.SPARK_MAX;
176+
}else if(motor instanceof SparkFlex){
177+
return MotorControllerType.SPARK_FLEX;
178+
}
179+
return null;
180+
}
181+
160182
public static SparkBaseConfig sparkConfig(SparkMotorType motor){
161183
SparkBaseConfig config = null;
162184
switch(motor.getControllerType()){

src/main/java/org/carlmontrobotics/lib199/MotorErrors.java

Lines changed: 17 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818

1919
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2020

21+
import org.carlmontrobotics.lib199.MotorControllerFactory;
22+
2123
public final class MotorErrors {
2224

2325
private static final Map<Integer, SparkBase> temperatureSparks = new ConcurrentSkipListMap<>();
@@ -183,18 +185,21 @@ private static void reportSparkTemp(int port, SparkBase spark) {
183185
System.err.println("Port " + port + " spark is operating at " + temp
184186
+ " degrees Celsius! It will be disabled until the robot code is restarted.");
185187
}
186-
if (spark.getClass() == SparkMax.class) {
187-
spark.configure(
188-
OVERHEAT_MAX_CONFIG,
189-
SparkBase.ResetMode.kNoResetSafeParameters,
190-
SparkBase.PersistMode.kNoPersistParameters);
191-
} else if (spark.getClass() == SparkFlex.class) {
192-
spark.configure(
193-
OVERHEAT_FLEX_CONFIG,
194-
SparkBase.ResetMode.kNoResetSafeParameters,
195-
SparkBase.PersistMode.kNoPersistParameters);
196-
}else{
197-
System.err.println("Unknown spark :(");
188+
switch(MotorControllerFactory.getControllerType(spark)){
189+
case SPARK_MAX:
190+
spark.configure(
191+
OVERHEAT_MAX_CONFIG,
192+
SparkBase.ResetMode.kNoResetSafeParameters,
193+
SparkBase.PersistMode.kNoPersistParameters);
194+
break;
195+
case SPARK_FLEX:
196+
spark.configure(
197+
OVERHEAT_FLEX_CONFIG,
198+
SparkBase.ResetMode.kNoResetSafeParameters,
199+
SparkBase.PersistMode.kNoPersistParameters);
200+
break;
201+
default:
202+
System.err.println("Unknown spark :(");
198203
}
199204
}
200205
}

src/main/java/org/carlmontrobotics/lib199/swerve/SwerveModule.java

Lines changed: 12 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66

77
import java.util.function.Supplier;
88

9+
import org.carlmontrobotics.lib199.MotorControllerType;
910
import org.carlmontrobotics.lib199.SparkMotorType;
1011
import org.mockito.internal.reporting.SmartPrinter;
1112

@@ -73,26 +74,26 @@ public enum ModuleType {FL, FR, BL, BR};
7374
private static final int ENCODER_POSITION_PERIOD_MS = 20;
7475
private int encoderAverageDepth = 2;
7576

76-
SparkMotorType driveMotorType;
77-
SparkMotorType turnMotorType;
77+
MotorControllerType driveMotorType;
78+
MotorControllerType turnMotorType;
7879

79-
public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, SparkMotorType driveMotorType, SparkMotorType turnMotorType, CANcoder turnEncoder,
80+
public SwerveModule(SwerveConfig config, ModuleType type, SparkBase drive, SparkBase turn, MotorControllerType driveMotorType, MotorControllerType turnMotorType, CANcoder turnEncoder,
8081
int arrIndex, Supplier<Float> pitchDegSupplier, Supplier<Float> rollDegSupplier) {
8182
this.driveMotorType = driveMotorType;
8283
this.turnMotorType = turnMotorType;
8384
switch(driveMotorType) {
84-
case NEO, NEO550, NEO_2, SOLO_VORTEX:
85+
case SPARK_MAX:
8586
driveConfig = new SparkMaxConfig();
8687
break;
87-
case VORTEX:
88+
case SPARK_FLEX:
8889
driveConfig = new SparkFlexConfig();
8990
break;
9091
}
9192
switch(turnMotorType) {
92-
case NEO, NEO550, NEO_2, SOLO_VORTEX:
93+
case SPARK_MAX:
9394
turnConfig = new SparkMaxConfig();
9495
break;
95-
case VORTEX:
96+
case SPARK_FLEX:
9697
turnConfig = new SparkFlexConfig();
9798
break;
9899
}
@@ -466,10 +467,10 @@ public void brake() {
466467
idleMode = IdleMode.kBrake;
467468
SparkBaseConfig config = null;
468469
switch(driveMotorType){
469-
case NEO, NEO550, NEO_2, SOLO_VORTEX:
470+
case SPARK_MAX:
470471
config = new SparkMaxConfig().idleMode(IdleMode.kBrake);
471472
break;
472-
case VORTEX:
473+
case SPARK_FLEX:
473474
config = new SparkFlexConfig().idleMode(IdleMode.kBrake);
474475
break;
475476
}
@@ -481,10 +482,10 @@ public void coast() {
481482
idleMode = IdleMode.kCoast;
482483
SparkBaseConfig config = null;
483484
switch(driveMotorType){
484-
case NEO, NEO550, NEO_2, SOLO_VORTEX:
485+
case SPARK_MAX:
485486
config = new SparkMaxConfig().idleMode(IdleMode.kCoast);
486487
break;
487-
case VORTEX:
488+
case SPARK_FLEX:
488489
config = new SparkFlexConfig().idleMode(IdleMode.kCoast);
489490
break;
490491
}

0 commit comments

Comments
 (0)