Skip to content

Commit 30068e6

Browse files
committed
rework spark max mocking
1 parent 6bef0d1 commit 30068e6

4 files changed

Lines changed: 28 additions & 21 deletions

File tree

src/main/java/frc/robot/lib/DummySparkMaxAnswer.java

Lines changed: 19 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
package frc.robot.lib;
22

3+
import com.revrobotics.CANSparkMax;
34
import com.revrobotics.RelativeEncoder;
45
import com.revrobotics.SparkMaxAnalogSensor;
56
import com.revrobotics.SparkMaxLimitSwitch;
@@ -15,26 +16,32 @@ public class DummySparkMaxAnswer extends REVLibErrorAnswer {
1516

1617
private static final long serialVersionUID = 2284848703213263465L;
1718

19+
public static final DummySparkMaxAnswer ANSWER = new DummySparkMaxAnswer();
20+
21+
public static final CANSparkMax DUMMY_SPARK_MAX = Mockito.mock(CANSparkMax.class, ANSWER);
22+
23+
public static final RelativeEncoder DUMMY_ENCODER = Mockito.mock(RelativeEncoder.class, REVLibErrorAnswer.ANSWER);
24+
public static final SparkMaxAnalogSensor DUMMY_ANALOG_SENSOR = Mockito.mock(SparkMaxAnalogSensor.class, REVLibErrorAnswer.ANSWER);
25+
public static final SparkMaxLimitSwitch DUMMY_LIMIT_SWITCH = Mockito.mock(SparkMaxLimitSwitch.class, REVLibErrorAnswer.ANSWER);
26+
public static final SparkMaxPIDController DUMMY_PID_CONTROLLER = Mockito.mock(SparkMaxPIDController.class, REVLibErrorAnswer.ANSWER);
27+
1828
@Override
1929
public Object answer(InvocationOnMock invocation) throws Throwable {
2030
Class<?> returnType = invocation.getMethod().getReturnType();
21-
if(returnType == RelativeEncoder.class || returnType == SparkMaxAnalogSensor.class || returnType == SparkMaxAnalogSensor.class || returnType == SparkMaxLimitSwitch.class) {
22-
return Mockito.mock(returnType, new REVLibErrorAnswer());
31+
if(returnType == RelativeEncoder.class) {
32+
return DUMMY_ENCODER;
33+
} else if(returnType == SparkMaxAnalogSensor.class) {
34+
return DUMMY_ANALOG_SENSOR;
35+
} else if(returnType == SparkMaxLimitSwitch.class) {
36+
return DUMMY_LIMIT_SWITCH;
2337
} else if(returnType == SparkMaxPIDController.class) {
24-
return Mockito.mock(SparkMaxPIDController.class, new REVLibErrorAnswer() {
25-
private static final long serialVersionUID = 558452215206948125L;
26-
@Override
27-
public Object answer(InvocationOnMock invocation) throws Throwable {
28-
if(invocation.getMethod().getReturnType() == AccelStrategy.class) {
29-
return AccelStrategy.kTrapezoidal;
30-
}
31-
return super.answer(invocation);
32-
}
33-
});
38+
return DUMMY_PID_CONTROLLER;
3439
} else if(returnType == MotorType.class) {
3540
return MotorType.kBrushless;
3641
} else if(returnType == IdleMode.class) {
3742
return IdleMode.kBrake;
43+
} else if(returnType == AccelStrategy.class) {
44+
return AccelStrategy.kTrapezoidal;
3845
}
3946
return super.answer(invocation);
4047
}

src/main/java/frc/robot/lib/MotorControllerFactory.java

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -74,12 +74,12 @@ public static WPI_TalonSRX createTalon(int id) {
7474
public static CANSparkMax createSparkMax(int id) {
7575
CANSparkMax spark;
7676
if (RobotBase.isReal()) {
77-
spark = new CachedSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
78-
if (spark.getFirmwareVersion() == 0) {
79-
spark.close();
80-
System.err.println("SparkMax on port: " + id + " is not connected!");
81-
return MotorErrors.createDummySparkMax();
82-
}
77+
spark = new CachedSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
78+
if (spark.getFirmwareVersion() == 0) {
79+
spark.close();
80+
System.err.println("SparkMax on port: " + id + " is not connected!");
81+
return MotorErrors.createDummySparkMax();
82+
}
8383
} else {
8484
spark = MockSparkMax.createMockSparkMax(id, CANSparkMaxLowLevel.MotorType.kBrushless);
8585
}

src/main/java/frc/robot/lib/MotorErrors.java

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,8 +9,6 @@
99
import com.revrobotics.CANSparkMax.FaultID;
1010
import com.revrobotics.REVLibError;
1111

12-
import org.mockito.Mockito;
13-
1412
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1513

1614
public final class MotorErrors {
@@ -98,7 +96,7 @@ public static void printSparkMaxErrorMessages() {
9896
}
9997

10098
public static CANSparkMax createDummySparkMax() {
101-
return Mockito.mock(CANSparkMax.class, new DummySparkMaxAnswer());
99+
return DummySparkMaxAnswer.DUMMY_SPARK_MAX;
102100
}
103101

104102
public static void reportSparkMaxTemp(CANSparkMax spark) {

src/main/java/frc/robot/lib/REVLibErrorAnswer.java

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,8 @@ public class REVLibErrorAnswer extends ReturnsSmartNulls {
99

1010
private static final long serialVersionUID = -561160298532167923L;
1111

12+
public static final REVLibErrorAnswer ANSWER = new REVLibErrorAnswer();
13+
1214
@Override
1315
public Object answer(InvocationOnMock invocation) throws Throwable {
1416
return invocation.getMethod().getReturnType().equals(REVLibError.class) ? REVLibError.kOk : super.answer(invocation);

0 commit comments

Comments
 (0)