1414import com .ctre .phoenix .motorcontrol .can .WPI_VictorSPX ;
1515import com .kauailabs .navx .frc .AHRS ;
1616
17- import edu .wpi .first .wpilibj .AnalogGyro ;
1817import edu .wpi .first .wpilibj .DigitalInput ;
1918import edu .wpi .first .wpilibj .DigitalSource ;
2019import edu .wpi .first .wpilibj .DoubleSolenoid ;
@@ -41,7 +40,7 @@ public class RobotMap {
4140 public static DigitalSource leftEncPort2 ;
4241 public static Encoder leftEncDist ;
4342 public static Encoder leftEncRate ;
44- public static WPI_TalonSRX dtLeftDrive ;
43+ public static WPI_TalonSRX dtLeftMaster ;
4544 public static WPI_VictorSPX dtLeftSlave ;
4645 public static SpeedControllerGroup dtLeft ;
4746 public static VelocityPIDController leftVelocityController ;
@@ -50,7 +49,7 @@ public class RobotMap {
5049 public static DigitalSource rightEncPort2 ;
5150 public static Encoder rightEncDist ;
5251 public static Encoder rightEncRate ;
53- public static WPI_TalonSRX dtRightDrive ;
52+ public static WPI_TalonSRX dtRightMaster ;
5453 public static WPI_VictorSPX dtRightSlave ;
5554 public static SpeedControllerGroup dtRight ;
5655 public static VelocityPIDController rightVelocityController ;
@@ -59,7 +58,6 @@ public class RobotMap {
5958 public static PIDSourceAverage distEncAvg ;
6059
6160 public static AHRS fancyGyro ;
62- public static AnalogGyro dtGyro ;
6361 public static DoubleSolenoid dtGear ;
6462
6563 /**
@@ -107,11 +105,11 @@ public RobotMap() {
107105 leftEncDist .setPIDSourceType (PIDSourceType .kDisplacement );
108106 leftEncRate = new Encoder (leftEncPort1 , leftEncPort2 );
109107 leftEncRate .setPIDSourceType (PIDSourceType .kRate );
110- dtLeftDrive = new WPI_TalonSRX (getPort ("LeftTalonSRXDrive " , 0 ));
111- configSRX (dtLeftDrive );
108+ dtLeftMaster = new WPI_TalonSRX (getPort ("LeftTalonSRXMaster " , 0 ));
109+ configSRX (dtLeftMaster );
112110 dtLeftSlave = new WPI_VictorSPX (getPort ("LeftTalonSPXSlave" , 1 ));
113111 configSPX (dtLeftSlave );
114- dtLeft = new SpeedControllerGroup (dtLeftDrive , dtLeftSlave );
112+ dtLeft = new SpeedControllerGroup (dtLeftMaster , dtLeftSlave );
115113
116114 leftVelocityController = new VelocityPIDController (Robot .getConst ("MoveLeftkP" , 1 ),
117115 Robot .getConst ("MoveLeftkI" , 0 ), Robot .getConst ("MoveLeftkD" , 0 ), 1 / Robot .getConst ("MaxSpeed" , 17 ),
@@ -128,11 +126,11 @@ public RobotMap() {
128126 rightEncDist .setPIDSourceType (PIDSourceType .kDisplacement );
129127 rightEncRate = new Encoder (leftEncPort1 , leftEncPort2 );
130128 rightEncRate .setPIDSourceType (PIDSourceType .kRate );
131- dtRightDrive = new WPI_TalonSRX (getPort ("RightTalonSRXDrive " , 2 ));
132- configSRX (dtRightDrive );
129+ dtRightMaster = new WPI_TalonSRX (getPort ("RightTalonSRXMaster " , 2 ));
130+ configSRX (dtRightMaster );
133131 dtRightSlave = new WPI_VictorSPX (getPort ("RightTalonSPXSlave" , 3 ));
134132 configSPX (dtRightSlave );
135- dtRight = new SpeedControllerGroup (dtRightDrive , dtRightSlave );
133+ dtRight = new SpeedControllerGroup (dtRightMaster , dtRightSlave );
136134
137135 rightVelocityController = new VelocityPIDController (Robot .getConst ("MoveRightkP" , 1 ),
138136 Robot .getConst ("MoveRightkI" , 0 ), Robot .getConst ("MoveRightkD" , 0 ), 1 / Robot .getConst ("MaxSpeed" , 17 ),
@@ -147,7 +145,6 @@ public RobotMap() {
147145
148146 distEncAvg = new PIDSourceAverage (leftEncDist , rightEncDist );
149147 fancyGyro = new AHRS (SerialPort .Port .kMXP );
150- dtGyro = new AnalogGyro (getPort ("Gyro" , 0 ));
151148 dtGear = new DoubleSolenoid (getPort ("1dtGearSolenoid" , 0 ), getPort ("2dtGearSolenoid" , 1 ));
152149 }
153150
0 commit comments