Skip to content

Commit a3866b2

Browse files
authored
Merge pull request #30 from DeepBlueRobotics/cancoder-sim-hints
Enable Swerve Simulation
2 parents ce91324 + f3df710 commit a3866b2

3 files changed

Lines changed: 36 additions & 6 deletions

File tree

src/main/java/org/carlmontrobotics/lib199/sim/MockedCANCoder.java

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
package org.carlmontrobotics.lib199.sim;
22

3+
import java.util.HashMap;
4+
35
import com.ctre.phoenix.sensors.CANCoder;
46
import com.ctre.phoenix.sensors.CANCoderSimCollection;
57

@@ -13,21 +15,34 @@ public class MockedCANCoder {
1315

1416
public static final double kCANCoderCPR = 4096;
1517

18+
private static final HashMap<Integer, MockedCANCoder> sims = new HashMap<>();
19+
1620
private int port;
1721
private SimDevice device;
1822
private SimDouble position; // Rotations - Continuous
23+
private SimDouble gearing;
1924
private CANCoderSimCollection sim;
2025

2126
public MockedCANCoder(CANCoder canCoder) {
2227
port = canCoder.getDeviceID();
2328
device = SimDevice.create("CANCoder", port);
2429
position = device.createDouble("count", Direction.kInput, 0);
30+
gearing = device.createDouble("gearing", Direction.kOutput, 1);
2531
sim = canCoder.getSimCollection();
2632
Lib199Subsystem.registerPeriodic(this::update);
33+
sims.put(port, this);
2734
}
2835

2936
public void update() {
3037
sim.setRawPosition((int) (position.get() * kCANCoderCPR));
3138
}
3239

40+
public void setGearing(double gearing) {
41+
this.gearing.set(gearing);
42+
}
43+
44+
public static void setGearing(int port, double gearing) {
45+
if(sims.containsKey(port)) sims.get(port).setGearing(gearing);
46+
}
47+
3348
}

src/main/java/org/carlmontrobotics/lib199/sim/MockedSparkEncoder.java

Lines changed: 18 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,24 +1,30 @@
11
package org.carlmontrobotics.lib199.sim;
22

3+
import java.util.HashMap;
4+
35
import com.revrobotics.REVLibError;
46

57
import edu.wpi.first.hal.SimDevice;
68
import edu.wpi.first.hal.SimDouble;
79
import edu.wpi.first.hal.SimDevice.Direction;
810

911
public class MockedSparkEncoder implements AutoCloseable {
12+
13+
private static final HashMap<Integer, MockedSparkEncoder> sims = new HashMap<>();
14+
1015
private SimDevice device;
1116
private SimDouble dpp;
1217
private SimDouble count;
18+
private SimDouble gearing;
1319
// Default value for a CANEncoder
1420
private final int countsPerRevolution = 4096;
1521

1622
public MockedSparkEncoder(int id) {
17-
// Match motor on CAN 0 with channels [0, 1], CAN 1 to channels [2, 3], etc.
18-
// Probably not the best way to do it but it works
19-
device = SimDevice.create("CANEncoder_SparkMax", id);
23+
device = SimDevice.create("RelativeEncoder", id);
2024
dpp = device.createDouble("distancePerPulse", Direction.kOutput, 1);
2125
count = device.createDouble("count", Direction.kInput, 0);
26+
gearing = device.createDouble("gearing", Direction.kOutput, 1);
27+
sims.put(id, this);
2228
}
2329

2430
public double getPosition() {
@@ -46,4 +52,13 @@ public double getPositionConversionFactor() {
4652
public void close() {
4753
device.close();
4854
}
55+
56+
public void setGearing(double gearing) {
57+
this.gearing.set(gearing);
58+
}
59+
60+
public static void setGearing(int port, double gearing) {
61+
if(sims.containsKey(port)) sims.get(port).setGearing(gearing);
62+
}
63+
4964
}

src/test/java/org/carlmontrobotics/lib199/sim/MockedSparkEncoderTest.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,11 @@ public void testDeviceCreation() {
3636
}
3737

3838
private void assertTestDeviceCreation(int id) {
39-
String deviceName = String.format("CANEncoder_SparkMax[%d]", id);
39+
String deviceName = String.format("RelativeEncoder[%d]", id);
4040
assertFalse(simDeviceExists(deviceName));
4141
try(SafelyClosable closableEncoder = createEncoder(id)) {
4242
assertTrue(simDeviceExists(deviceName));
43-
SimDeviceSim sim = new SimDeviceSim("CANEncoder_SparkMax", id);
43+
SimDeviceSim sim = new SimDeviceSim("RelativeEncoder", id);
4444
assertEquals(2, Stream.of(sim.enumerateValues())
4545
.map(info -> info.name)
4646
.distinct()
@@ -102,7 +102,7 @@ private void withEncoders(EncoderTest func) {
102102

103103
private void withEncoder(int id, EncoderTest func) {
104104
try(SafelyClosable encoder = createEncoder(id)) {
105-
SimDeviceSim sim = new SimDeviceSim("CANEncoder_SparkMax", id);
105+
SimDeviceSim sim = new SimDeviceSim("RelativeEncoder", id);
106106
SimDouble dpp = sim.getDouble("distancePerPulse");
107107
SimDouble count = sim.getDouble("count");
108108
assertNotNull(dpp);

0 commit comments

Comments
 (0)