Skip to content

Commit 6a60bf8

Browse files
committed
resolved comments
1 parent a62be8b commit 6a60bf8

File tree

4 files changed

+7
-7
lines changed

4 files changed

+7
-7
lines changed

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ public static SparkMax createSparkMax(int id, MotorConfig motorConfig, SparkBase
7979
MotorErrors.reportError(spark.configure(
8080
config,
8181
SparkBase.ResetMode.kResetSafeParameters,
82-
SparkBase.PersistMode.kNoPersistParameters
82+
SparkBase.PersistMode.kPersistParameters
8383
));
8484
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);
8585
MotorErrors.checkSparkErrors(spark);
@@ -110,7 +110,7 @@ public static SparkFlex createSparkFlex(int id, MotorConfig motorConfig, SparkBa
110110
MotorErrors.reportError(spark.configure(
111111
config,
112112
SparkBase.ResetMode.kResetSafeParameters,
113-
SparkBase.PersistMode.kNoPersistParameters
113+
SparkBase.PersistMode.kPersistParameters
114114
));
115115

116116
MotorErrors.reportSparkTemp(spark, motorConfig.temperatureLimitCelsius);

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,8 @@ public SparkVelocityPIDController(String name, SparkBase spark, double defaultP,
3333
this.name = name;
3434
this.targetSpeed = targetSpeed;
3535
this.tolerance = tolerance;
36-
37-
spark.configure(MotorControllerFactory.sparkConfig(MotorConfig.NEO).apply(
36+
37+
spark.configure(MotorControllerType.getMotorControllerType(spark).createConfig().apply(
3838
new ClosedLoopConfig().pid(
3939
this.currentP = defaultP,
4040
this.currentI = defaultI,
@@ -85,7 +85,7 @@ public double calculateFF(double velocity) {
8585
}
8686

8787
private void instantClosedLoopConfig(ClosedLoopConfig clConfig) {
88-
spark.configure(MotorControllerFactory.sparkConfig(MotorConfig.NEO).apply(clConfig), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
88+
spark.configure(MotorControllerType.getMotorControllerType(spark).createConfig().apply(clConfig), ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
8989
}
9090

9191
@Override

src/main/java/org/carlmontrobotics/lib199/sim/MockSparkBase.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ public class MockSparkBase extends MockedMotorBase {
5252
private SparkAnalogSensorSim analogSensorImpl = null;
5353
private final String name;
5454

55-
public enum NEOType { //is it fine if we make it public so that MotorControllerFactory can access it?
55+
public enum NEOType {
5656
NEO(DCMotor.getNEO(1)),
5757
NEO550(DCMotor.getNeo550(1)),
5858
VORTEX(DCMotor.getNeoVortex(1)),

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -446,7 +446,7 @@ public void updateSmartDashboard() {
446446
}
447447

448448
public void toggleMode() {
449-
if (driveConfigAccessor.getIdleMode() == IdleMode.kBrake && turnConfigAccessor.getIdleMode() == IdleMode.kCoast) coast();
449+
if (driveConfigAccessor.getIdleMode() == IdleMode.kBrake && turnConfigAccessor.getIdleMode() == IdleMode.kBrake) coast();
450450
else brake();
451451
}
452452

0 commit comments

Comments
 (0)