Skip to content

Commit 1be3fcf

Browse files
authored
Merge pull request #41 from DeepBlueRobotics/no-temp-limit
Fix Sporadic Temperature Reporting
2 parents 09af73a + c6ef41a commit 1be3fcf

7 files changed

Lines changed: 126 additions & 73 deletions

File tree

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

Lines changed: 0 additions & 15 deletions
This file was deleted.
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
package org.carlmontrobotics.lib199;
2+
3+
public class MotorConfig {
4+
5+
public static final MotorConfig NEO = new MotorConfig(70, 40);
6+
public static final MotorConfig NEO_550 = new MotorConfig(40, 20);
7+
8+
public final int temperatureLimitCelsius, currentLimitAmps;
9+
10+
public MotorConfig(int temperatureLimitCelsius, int currentLimitAmps) {
11+
this.temperatureLimitCelsius = temperatureLimitCelsius;
12+
this.currentLimitAmps = currentLimitAmps;
13+
}
14+
15+
}

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

Lines changed: 2 additions & 3 deletions
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;
@@ -125,13 +124,13 @@ public static CANSparkMax createSparkMax(int id, MotorConfig config) {
125124
spark = MockSparkMax.createMockSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
126125
}
127126

128-
MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimit);
127+
MotorErrors.reportSparkMaxTemp(spark, config.temperatureLimitCelsius);
129128

130129
MotorErrors.reportError(spark.restoreFactoryDefaults());
131130
MotorErrors.reportError(spark.follow(ExternalFollower.kFollowerDisabled, 0));
132131
MotorErrors.reportError(spark.setIdleMode(IdleMode.kBrake));
133132
MotorErrors.reportError(spark.enableVoltageCompensation(12));
134-
MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimit));
133+
MotorErrors.reportError(spark.setSmartCurrentLimit(config.currentLimitAmps));
135134

136135
MotorErrors.checkSparkMaxErrors(spark);
137136

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

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

33
import java.util.Arrays;
44
import java.util.concurrent.ConcurrentHashMap;
5-
import java.util.concurrent.CopyOnWriteArrayList;
65

76
import com.ctre.phoenix.ErrorCode;
87
import com.revrobotics.CANSparkMax;
@@ -15,12 +14,15 @@ public final class MotorErrors {
1514

1615
private static final ConcurrentHashMap<Integer, CANSparkMax> temperatureSparks = new ConcurrentHashMap<>();
1716
private static final ConcurrentHashMap<Integer, Integer> sparkTemperatureLimits = new ConcurrentHashMap<>();
18-
private static final CopyOnWriteArrayList<Integer> overheatedSparks = new CopyOnWriteArrayList<>();
17+
private static final ConcurrentHashMap<Integer, Integer> overheatedSparks = new ConcurrentHashMap<>();
1918
private static final ConcurrentHashMap<CANSparkMax, Short> flags = new ConcurrentHashMap<>();
2019
private static final ConcurrentHashMap<CANSparkMax, Short> stickyFlags = new ConcurrentHashMap<>();
2120

21+
public static final int kOverheatTripCount = 5;
22+
2223
static {
2324
Lib199Subsystem.registerAsyncPeriodic(MotorErrors::doReportSparkMaxTemp);
25+
Lib199Subsystem.registerAsyncPeriodic(MotorErrors::printSparkMaxErrorMessages);
2426
}
2527

2628
public static void reportError(ErrorCode error) {
@@ -108,16 +110,30 @@ public static void reportSparkMaxTemp(CANSparkMax spark, int temperatureLimit) {
108110
int id = spark.getDeviceId();
109111
temperatureSparks.put(id, spark);
110112
sparkTemperatureLimits.put(id, temperatureLimit);
113+
overheatedSparks.put(id, 0);
111114
}
112115

113116
public static void doReportSparkMaxTemp() {
114117
temperatureSparks.forEach((port, spark) -> {
115118
double temp = spark.getMotorTemperature();
119+
double limit = sparkTemperatureLimits.get(port);
120+
int numTrips = overheatedSparks.get(port);
116121
SmartDashboard.putNumber("Port " + port + " Spark Max Temp", temp);
122+
123+
if(numTrips < kOverheatTripCount) {
124+
if(temp > limit) {
125+
overheatedSparks.put(port, ++numTrips);
126+
} else {
127+
overheatedSparks.put(port, 0);
128+
}
129+
}
130+
117131
// Check if temperature exceeds the setpoint or if the controller has already overheated to prevent other code from resetting the current limit after the controller has cooled
118-
if(temp >= sparkTemperatureLimits.get(port) || overheatedSparks.contains(port)) {
119-
if(!overheatedSparks.contains(port)) {
120-
overheatedSparks.add(port);
132+
if(numTrips >= kOverheatTripCount) {
133+
if(numTrips < kOverheatTripCount + 1) {
134+
// Set trip count to kOverheatTripCount + 1 to flag that an error message has already been printed
135+
// This prevents the error message from being re-printed every time the periodic method is run
136+
overheatedSparks.put(port, kOverheatTripCount + 1);
121137
System.err.println("Port " + port + " spark max is operating at " + temp + " degrees Celsius! It will be disabled until the robot code is restarted.");
122138
}
123139
spark.setSmartCurrentLimit(1);

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

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

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: 87 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,11 @@
22

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

8+
import java.util.concurrent.atomic.AtomicBoolean;
9+
710
import com.ctre.phoenix.ErrorCode;
811
import com.revrobotics.REVLibError;
912
import com.revrobotics.CANSparkMax;
@@ -45,7 +48,7 @@ public static interface TemperatureSparkMax {
4548

4649
public static class Instance {
4750

48-
private int smartCurrentLimit = 50;
51+
private int smartCurrentLimit = MotorConfig.NEO.currentLimitAmps;
4952
private double temperature = 30;
5053
private final int id;
5154

@@ -69,24 +72,14 @@ public REVLibError setSmartCurrentLimit(int limit) {
6972
smartCurrentLimit = limit;
7073
return REVLibError.kOk;
7174
}
72-
75+
7376
public int getDeviceId() {
7477
return id;
7578
}
7679
}
7780

7881
}
7982

80-
private static final Object asyncPeriodicNotifier = new Object();
81-
82-
static {
83-
Lib199Subsystem.registerAsyncPeriodic(() -> {
84-
synchronized(asyncPeriodicNotifier) {
85-
asyncPeriodicNotifier.notifyAll();
86-
}
87-
});
88-
}
89-
9083
@Test
9184
public void testOkErrors() {
9285
errStream.reset();
@@ -99,7 +92,7 @@ public void testOkErrors() {
9992
assertEquals(0, errStream.toByteArray().length);
10093
MotorErrors.reportErrors((REVLibError)null, null);
10194
assertEquals(0, errStream.toByteArray().length);
102-
95+
10396
// Ok Status
10497
MotorErrors.reportError(ErrorCode.OK);
10598
assertEquals(0, errStream.toByteArray().length);
@@ -165,53 +158,99 @@ public void testDummySparkMax() {
165158

166159
@Test
167160
public void testReportSparkMaxTemp() {
161+
assertTrue(MotorErrors.kOverheatTripCount > 0);
162+
168163
doTestReportSparkMaxTemp(0);
169164
doTestReportSparkMaxTemp(1);
170165
doTestReportSparkMaxTemp(2);
171166
}
172167

173168
private void doTestReportSparkMaxTemp(int id) {
174169
TemperatureSparkMax spark = (TemperatureSparkMax)Mocks.createMock(CANSparkMax.class, new TemperatureSparkMax.Instance(id), TemperatureSparkMax.class);
175-
MotorErrors.reportSparkMaxTemp((CANSparkMax)spark, 40);
176-
spark.setSmartCurrentLimit(50);
177-
spark.setTemperature(20);
178-
runAsyncPeriodic();
179170
String smartDashboardKey = "Port " + id + " Spark Max Temp";
180-
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
181-
assertEquals(50, spark.getSmartCurrentLimit());
182-
spark.setTemperature(20);
183-
runAsyncPeriodic();
184-
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
185-
assertEquals(50, spark.getSmartCurrentLimit());
186-
assertEquals(0, errStream.size());
187-
spark.setTemperature(40);
188-
runAsyncPeriodic();
189-
assertEquals(40, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
190-
assertEquals(1, spark.getSmartCurrentLimit());
191-
assertNotEquals(0, errStream.size());
192-
errStream.reset();
193-
spark.setTemperature(50);
194-
runAsyncPeriodic();
195-
assertEquals(50, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
196-
assertEquals(1, spark.getSmartCurrentLimit());
197-
spark.setTemperature(20);
198-
runAsyncPeriodic();
199-
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
200-
assertEquals(1, spark.getSmartCurrentLimit());
201-
assertEquals(0, errStream.size());
202-
}
171+
MotorErrors.reportSparkMaxTemp((CANSparkMax)spark, 40);
172+
173+
try(AutoCloseable asyncBlock = blockAsyncPeriodic()) {
174+
spark.setTemperature(20);
175+
spark.setSmartCurrentLimit(50);
176+
MotorErrors.doReportSparkMaxTemp();
177+
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
178+
assertEquals(50, spark.getSmartCurrentLimit());
179+
180+
spark.setTemperature(20);
181+
spark.setSmartCurrentLimit(50);
182+
MotorErrors.doReportSparkMaxTemp();
183+
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
184+
assertEquals(50, spark.getSmartCurrentLimit());
203185

204-
// Ensures an update to the asynchronous periodic thread is run
205-
private void runAsyncPeriodic() {
206-
try {
207-
synchronized(asyncPeriodicNotifier) {
208-
// Run twice because we don't know in what order we're called, so make sure all periodic methods are run twice
209-
asyncPeriodicNotifier.wait();
210-
asyncPeriodicNotifier.wait();
186+
if(MotorErrors.kOverheatTripCount > 1) {
187+
spark.setTemperature(51);
188+
spark.setSmartCurrentLimit(50);
189+
MotorErrors.doReportSparkMaxTemp();
190+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
191+
assertEquals(50, spark.getSmartCurrentLimit());
192+
193+
spark.setTemperature(20);
194+
spark.setSmartCurrentLimit(50);
195+
MotorErrors.doReportSparkMaxTemp();
196+
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
197+
assertEquals(50, spark.getSmartCurrentLimit());
198+
}
199+
200+
assertEquals(0, errStream.size());
201+
202+
for(int i = 0; i < MotorErrors.kOverheatTripCount; i++) {
203+
assertEquals(50, spark.getSmartCurrentLimit());
204+
assertEquals(0, errStream.size());
205+
206+
spark.setTemperature(51);
207+
spark.setSmartCurrentLimit(50);
208+
MotorErrors.doReportSparkMaxTemp();
209+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
211210
}
212-
} catch(InterruptedException e) {
211+
212+
assertNotEquals(0, errStream.size());
213+
errStream.reset();
214+
215+
spark.setTemperature(51);
216+
spark.setSmartCurrentLimit(50);
217+
MotorErrors.doReportSparkMaxTemp();
218+
assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
219+
assertEquals(1, spark.getSmartCurrentLimit());
220+
221+
spark.setTemperature(20);
222+
spark.setSmartCurrentLimit(50);
223+
MotorErrors.doReportSparkMaxTemp();
224+
assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01);
225+
assertEquals(1, spark.getSmartCurrentLimit());
226+
227+
assertEquals(0, errStream.size());
228+
} catch(Exception e) {
213229
assumeNoException(e);
214230
}
215231
}
216232

233+
// Blocks the Lib199Subsystem's async thread until closed
234+
private AutoCloseable blockAsyncPeriodic() {
235+
AtomicBoolean block = new AtomicBoolean(true);
236+
Object lock = new Object();
237+
Lib199Subsystem.registerAsyncPeriodic(() -> {
238+
synchronized(lock) {
239+
while(block.get()) {
240+
try {
241+
lock.wait();
242+
} catch(InterruptedException e) {
243+
assumeNoException(e);
244+
}
245+
}
246+
}
247+
});
248+
return () -> {
249+
block.set(false);
250+
synchronized(lock) {
251+
lock.notifyAll();
252+
}
253+
};
254+
}
255+
217256
}

0 commit comments

Comments
 (0)