Skip to content

Commit 58338f5

Browse files
committed
add simulation support for CANCoders
1 parent 3c0028f commit 58338f5

2 files changed

Lines changed: 40 additions & 0 deletions

File tree

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

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
import com.ctre.phoenix.motorcontrol.NeutralMode;
1111
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
1212
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
13+
import com.ctre.phoenix.sensors.CANCoder;
1314
import com.revrobotics.CANSparkMax;
1415
import com.revrobotics.CANSparkMax.ExternalFollower;
1516
import com.revrobotics.CANSparkMax.IdleMode;
@@ -21,6 +22,7 @@
2122
import frc.robot.lib.sim.MockSparkMax;
2223
import frc.robot.lib.sim.MockTalonSRX;
2324
import frc.robot.lib.sim.MockVictorSPX;
25+
import frc.robot.lib.sim.MockedCANCoder;
2426

2527
/**
2628
* Add your docs here.
@@ -108,4 +110,10 @@ public static CANSparkMax createSparkMax(int id, int temperatureLimit) {
108110

109111
return spark;
110112
}
113+
114+
public static CANCoder createCANCoder(int port) {
115+
CANCoder canCoder = new CANCoder(port);
116+
if(RobotBase.isSimulation()) new MockedCANCoder(canCoder);
117+
return canCoder;
118+
}
111119
}
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
package frc.robot.lib.sim;
2+
3+
import com.ctre.phoenix.sensors.CANCoder;
4+
import com.ctre.phoenix.sensors.CANCoderSimCollection;
5+
6+
import edu.wpi.first.hal.SimDevice;
7+
import edu.wpi.first.hal.SimDevice.Direction;
8+
import frc.robot.lib.Lib199Subsystem;
9+
import edu.wpi.first.hal.SimDouble;
10+
11+
public class MockedCANCoder {
12+
13+
public static final double kCANCoderCPR = 4096;
14+
15+
private int port;
16+
private SimDevice device;
17+
private SimDouble position; // Rotations - Continuous
18+
private CANCoderSimCollection sim;
19+
20+
public MockedCANCoder(CANCoder canCoder) {
21+
port = canCoder.getDeviceID();
22+
device = SimDevice.create("CANCoder", port);
23+
position = device.createDouble("count", Direction.kInput, 0);
24+
sim = canCoder.getSimCollection();
25+
Lib199Subsystem.registerPeriodic(this::update);
26+
}
27+
28+
public void update() {
29+
sim.setRawPosition((int) (position.get() * kCANCoderCPR));
30+
}
31+
32+
}

0 commit comments

Comments
 (0)