You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Copy file name to clipboardExpand all lines: src/main/java/org/carlmontrobotics/lib199/MotorErrors.java
+4-4Lines changed: 4 additions & 4 deletions
Original file line number
Diff line number
Diff line change
@@ -120,12 +120,12 @@ public static void doReportSparkMaxTemp() {
120
120
intnumTrips = overheatedSparks.get(port);
121
121
SmartDashboard.putNumber("Port " + port + " Spark Max Temp", temp);
122
122
123
-
if(temp > limit) {
124
-
if(numTrips < kOverheatTripCount) {
123
+
if(numTrips < kOverheatTripCount) {
124
+
if(temp > limit) {
125
125
overheatedSparks.put(port, ++numTrips);
126
+
} else {
127
+
overheatedSparks.put(port, 0);
126
128
}
127
-
} elseif(numTrips < kOverheatTripCount) {
128
-
overheatedSparks.put(port, 0);
129
129
}
130
130
131
131
// 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
0 commit comments