Skip to content

Commit c1eee3c

Browse files
committed
fix #37
1 parent 37861e4 commit c1eee3c

6 files changed

Lines changed: 51 additions & 17 deletions

File tree

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.carlmontrobotics;
1+
package org.carlmontrobotics.lib199;
22

33
public class MotorConfig {
44

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
import com.revrobotics.CANSparkMaxLowLevel;
1818
import com.revrobotics.SparkMaxPIDController;
1919

20-
import org.carlmontrobotics.MotorConfig;
2120
import org.carlmontrobotics.lib199.sim.MockSparkMax;
2221
import org.carlmontrobotics.lib199.sim.MockTalonSRX;
2322
import org.carlmontrobotics.lib199.sim.MockVictorSPX;

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

Lines changed: 14 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package org.carlmontrobotics.lib199;
22

3-
import java.util.ArrayList;
43
import java.util.Arrays;
54
import java.util.HashMap;
65

@@ -117,14 +116,25 @@ public static void reportSparkMaxTemp(CANSparkMax spark, int temperatureLimit) {
117116
public static void doReportSparkMaxTemp() {
118117
temperatureSparks.forEach((port, spark) -> {
119118
double temp = spark.getMotorTemperature();
119+
double limit = sparkTemperatureLimits.get(port);
120+
int numTrips = overheatedSparks.get(port);
120121
SmartDashboard.putNumber("Port " + port + " Spark Max Temp", temp);
122+
123+
if(temp > limit) {
124+
if(numTrips < kOverheatTripCount) {
125+
overheatedSparks.put(port, ++numTrips);
126+
}
127+
} else {
128+
overheatedSparks.put(port, 0);
129+
}
130+
121131
// Check if temperature exceeds the setpoint or if the contoller has already overheated to prevent other code from resetting the current limit after the controller has cooled
122-
if(temp >= sparkTemperatureLimits.get(port) || overheatedSparks.get(port) >= kOverheatTripCount) {
123-
if(overheatedSparks.get(port) < kOverheatTripCount + 1) {
132+
if(numTrips >= kOverheatTripCount) {
133+
if(numTrips < kOverheatTripCount + 1) {
124134
overheatedSparks.put(port, kOverheatTripCount + 1);
125135
System.err.println("Port " + port + " spark max is operating at " + temp + " degrees Celsius! It will be disabled until the robot code is restarted.");
126136
}
127-
// spark.setSmartCurrentLimit(1);
137+
spark.setSmartCurrentLimit(1);
128138
}
129139
});
130140
}

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,7 @@ private double calculateAntiGravitationalA(Float gyroPitchDeg, Float gyroRollDeg
174174
double g = 9.81; //meters per second squared
175175
// gravitationalA is estimated to work for small angles, not 100% accurate at large angles
176176
double antiGravitationalA = g * (modulePitchComponent * Math.sin(Math.PI * gyroPitchDeg / 180) - moduleRollComponent * Math.sin(Math.PI * gyroRollDeg / 180));
177-
SmartDashboard.putNumber("AntiGravitational accelration", antiGravitationalA);
177+
SmartDashboard.putNumber("AntiGravitational acceleration", antiGravitationalA);
178178
return antiGravitationalA;
179179
}
180180
/**

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

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,6 @@
22

33
import static org.junit.Assert.assertEquals;
44

5-
import org.carlmontrobotics.MotorConfig;
65
import org.carlmontrobotics.lib199.testUtils.ErrStreamTest;
76
import org.carlmontrobotics.lib199.testUtils.SimDeviceTestRule;
87
import org.junit.ClassRule;

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

Lines changed: 35 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
import static org.junit.Assert.assertEquals;
44
import static org.junit.Assert.assertNotEquals;
5+
import static org.junit.Assert.assertTrue;
56

67
import com.ctre.phoenix.ErrorCode;
78
import com.revrobotics.REVLibError;
@@ -45,7 +46,7 @@ public static interface TemperatureSparkMax {
4546

4647
public static class Instance {
4748

48-
private int smartCurrentLimit = 50;
49+
private int smartCurrentLimit = MotorConfig.NEO.currentLimit;
4950
private double temperature = 30;
5051
private final int id;
5152

@@ -155,40 +156,65 @@ public void testDummySparkMax() {
155156

156157
@Test
157158
public void testReportSparkMaxTemp() {
158-
if(true) return;
159+
assertTrue(MotorErrors.kOverheatTripCount > 0);
160+
159161
doTestReportSparkMaxTemp(0);
160162
doTestReportSparkMaxTemp(1);
161163
doTestReportSparkMaxTemp(2);
162164
}
163165

164166
private void doTestReportSparkMaxTemp(int id) {
165167
TemperatureSparkMax spark = (TemperatureSparkMax)Mocks.createMock(CANSparkMax.class, new TemperatureSparkMax.Instance(id), TemperatureSparkMax.class);
168+
String smartDashboardKey = "Port " + id + " Spark Max Temp";
166169
MotorErrors.reportSparkMaxTemp((CANSparkMax)spark, 40);
167170
spark.setSmartCurrentLimit(50);
171+
168172
spark.setTemperature(20);
169173
CommandScheduler.getInstance().run();
170-
String smartDashboardKey = "Port " + id + " Spark Max Temp";
171174
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
172175
assertEquals(50, spark.getSmartCurrentLimit());
176+
173177
spark.setTemperature(20);
174178
CommandScheduler.getInstance().run();
175179
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
176180
assertEquals(50, spark.getSmartCurrentLimit());
181+
182+
if(MotorErrors.kOverheatTripCount > 1) {
183+
spark.setTemperature(51);
184+
CommandScheduler.getInstance().run();
185+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
186+
assertEquals(50, spark.getSmartCurrentLimit());
187+
188+
spark.setTemperature(20);
189+
CommandScheduler.getInstance().run();
190+
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
191+
assertEquals(50, spark.getSmartCurrentLimit());
192+
}
193+
177194
assertEquals(0, errStream.size());
178-
spark.setTemperature(40);
179-
CommandScheduler.getInstance().run();
180-
assertEquals(40, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
181-
assertEquals(1, spark.getSmartCurrentLimit());
195+
196+
for(int i = 0; i < MotorErrors.kOverheatTripCount; i++) {
197+
assertEquals(50, spark.getSmartCurrentLimit());
198+
assertEquals(0, errStream.size());
199+
200+
spark.setTemperature(51);
201+
CommandScheduler.getInstance().run();
202+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
203+
}
204+
182205
assertNotEquals(0, errStream.size());
183206
errStream.reset();
184-
spark.setTemperature(50);
207+
208+
spark.setTemperature(51);
185209
CommandScheduler.getInstance().run();
186-
assertEquals(50, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
210+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
187211
assertEquals(1, spark.getSmartCurrentLimit());
212+
188213
spark.setTemperature(20);
189214
CommandScheduler.getInstance().run();
190215
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
191216
assertEquals(1, spark.getSmartCurrentLimit());
217+
192218
assertEquals(0, errStream.size());
193219
}
194220

0 commit comments

Comments
 (0)