Skip to content

Commit 1b2d901

Browse files
committed
add units to MotorConfig
1 parent 32510fd commit 1b2d901

3 files changed

Lines changed: 7 additions & 7 deletions

File tree

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,11 @@ public class MotorConfig {
55
public static final MotorConfig NEO = new MotorConfig(70, 40);
66
public static final MotorConfig NEO_550 = new MotorConfig(40, 20);
77

8-
public final int temperatureLimit, currentLimit;
8+
public final int temperatureLimitCelsius, currentLimitAmps;
99

10-
public MotorConfig(int temperatureLimit, int currentLimit) {
11-
this.temperatureLimit = temperatureLimit;
12-
this.currentLimit = currentLimit;
10+
public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps) {
11+
this.temperatureLimitCelsius = temperatureLimitCelsius;
12+
this.currentLimitAmps = currentLimitAmps;
1313
}
1414

1515
}

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -129,13 +129,13 @@ public static CANSparkMax createSparkMax(int id, MotorConfig config) {
129129
spark = MockSparkMax.createMockSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
130130
}
131131

132-
MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimit);
132+
MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimitCelsius);
133133

134134
MotorErrors.reportError(spark.restoreFactoryDefaults());
135135
MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0));
136136
MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake));
137137
MotorErrors.reportError(spark.enableVoltageCompensation(12));
138-
MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimit));
138+
MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimitAmps));
139139

140140
MotorErrors.checkSparkMaxErrors(spark);
141141

src/test/java/org/carlmontrobotics/lib199/MotorErrorsTest.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,7 @@ public static interface TemperatureSparkMax {
4646

4747
public static class Instance {
4848

49-
private int smartCurrentLimit = MotorConfig.NEO.currentLimit;
49+
private int smartCurrentLimit = MotorConfig.NEO.currentLimitAmps;
5050
private double temperature = 30;
5151
private final int id;
5252

0 commit comments

Comments
 (0)