|
2 | 2 |
|
3 | 3 | import static org.junit.Assert.assertEquals; |
4 | 4 | import static org.junit.Assert.assertNotEquals; |
| 5 | +import static org.junit.Assert.assertTrue; |
5 | 6 |
|
6 | 7 | import com.ctre.phoenix.ErrorCode; |
7 | 8 | import com.revrobotics.REVLibError; |
@@ -45,7 +46,7 @@ public static interface TemperatureSparkMax { |
45 | 46 |
|
46 | 47 | public static class Instance { |
47 | 48 |
|
48 | | - private int smartCurrentLimit = 50; |
| 49 | + private int smartCurrentLimit = MotorConfig.NEO.currentLimit; |
49 | 50 | private double temperature = 30; |
50 | 51 | private final int id; |
51 | 52 |
|
@@ -155,40 +156,65 @@ public void testDummySparkMax() { |
155 | 156 |
|
156 | 157 | @Test |
157 | 158 | public void testReportSparkMaxTemp() { |
158 | | - if(true) return; |
| 159 | + assertTrue(MotorErrors.kOverheatTripCount > 0); |
| 160 | + |
159 | 161 | doTestReportSparkMaxTemp(0); |
160 | 162 | doTestReportSparkMaxTemp(1); |
161 | 163 | doTestReportSparkMaxTemp(2); |
162 | 164 | } |
163 | 165 |
|
164 | 166 | private void doTestReportSparkMaxTemp(int id) { |
165 | 167 | TemperatureSparkMax spark = (TemperatureSparkMax)Mocks.createMock(CANSparkMax.class, new TemperatureSparkMax.Instance(id), TemperatureSparkMax.class); |
| 168 | + String smartDashboardKey = "Port " + id + " Spark Max Temp"; |
166 | 169 | MotorErrors.reportSparkMaxTemp((CANSparkMax)spark, 40); |
167 | 170 | spark.setSmartCurrentLimit(50); |
| 171 | + |
168 | 172 | spark.setTemperature(20); |
169 | 173 | CommandScheduler.getInstance().run(); |
170 | | - String smartDashboardKey = "Port " + id + " Spark Max Temp"; |
171 | 174 | assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01); |
172 | 175 | assertEquals(50, spark.getSmartCurrentLimit()); |
| 176 | + |
173 | 177 | spark.setTemperature(20); |
174 | 178 | CommandScheduler.getInstance().run(); |
175 | 179 | assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01); |
176 | 180 | 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 | + |
177 | 194 | 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 | + |
182 | 205 | assertNotEquals(0, errStream.size()); |
183 | 206 | errStream.reset(); |
184 | | - spark.setTemperature(50); |
| 207 | + |
| 208 | + spark.setTemperature(51); |
185 | 209 | CommandScheduler.getInstance().run(); |
186 | | - assertEquals(50, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01); |
| 210 | + assertEquals(51, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01); |
187 | 211 | assertEquals(1, spark.getSmartCurrentLimit()); |
| 212 | + |
188 | 213 | spark.setTemperature(20); |
189 | 214 | CommandScheduler.getInstance().run(); |
190 | 215 | assertEquals(20, SmartDashboard.getNumber(smartDashboardKey, 0), 0.01); |
191 | 216 | assertEquals(1, spark.getSmartCurrentLimit()); |
| 217 | + |
192 | 218 | assertEquals(0, errStream.size()); |
193 | 219 | } |
194 | 220 |
|
|
0 commit comments