11package org .carlmontrobotics .lib199 .sim ;
22
3+ import java .util .HashMap ;
4+
35import com .ctre .phoenix .sensors .CANCoder ;
46import com .ctre .phoenix .sensors .CANCoderSimCollection ;
57
@@ -13,21 +15,50 @@ 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 motorId ;
24+ private SimDouble motorType ;
25+ private SimDouble gearing ;
1926 private CANCoderSimCollection sim ;
2027
2128 public MockedCANCoder (CANCoder canCoder ) {
2229 port = canCoder .getDeviceID ();
2330 device = SimDevice .create ("CANCoder" , port );
2431 position = device .createDouble ("count" , Direction .kInput , 0 );
32+ motorId = device .createDouble ("motorId" , Direction .kOutput , -1 );
33+ motorType = device .createDouble ("motor" , Direction .kOutput , MotorType .NONE .id );
34+ gearing = device .createDouble ("gearing" , Direction .kOutput , 1 );
2535 sim = canCoder .getSimCollection ();
2636 Lib199Subsystem .registerPeriodic (this ::update );
37+ sims .put (port , this );
2738 }
2839
2940 public void update () {
3041 sim .setRawPosition ((int ) (position .get () * kCANCoderCPR ));
3142 }
3243
44+ public void linkMotor (int motorId , MotorType motorType , double gearing ) {
45+ this .motorId .set (motorId );
46+ this .motorType .set (motorType .id );
47+ this .gearing .set (gearing );
48+ }
49+
50+ public static void linkMotor (int canCoderPort , int motorId , MotorType motorType , double gearing ) {
51+ if (sims .containsKey (canCoderPort )) sims .get (canCoderPort ).linkMotor (motorId , motorType , gearing );
52+ }
53+
54+ public static enum MotorType {
55+ NONE (0 ), TALON (1 ), VICTOR (2 ), SPARKMAX (3 );
56+
57+ public final int id ;
58+
59+ private MotorType (int id ) {
60+ this .id = id ;
61+ }
62+ }
63+
3364}
0 commit comments