88package org .usfirst .frc .team199 .Robot2018 ;
99
1010import com .ctre .phoenix .motorcontrol .can .WPI_TalonSRX ;
11+ import com .ctre .phoenix .motorcontrol .can .WPI_VictorSPX ;
1112import com .kauailabs .navx .frc .AHRS ;
1213
1314import edu .wpi .first .wpilibj .AnalogGyro ;
@@ -38,12 +39,12 @@ public class RobotMap {
3839
3940 public static Encoder leftEnc ;
4041 public static WPI_TalonSRX dtLeftDrive ;
41- public static WPI_TalonSRX dtLeftSlave ;
42+ public static WPI_VictorSPX dtLeftSlave ;
4243 public static SpeedControllerGroup dtLeft ;
4344
4445 public static Encoder rightEnc ;
4546 public static WPI_TalonSRX dtRightDrive ;
46- public static WPI_TalonSRX dtRightSlave ;
47+ public static WPI_VictorSPX dtRightSlave ;
4748 public static SpeedControllerGroup dtRight ;
4849 public static DifferentialDrive robotDrive ;
4950 public static PIDController turnController ;
@@ -69,21 +70,36 @@ private void configSRX(WPI_TalonSRX mc) {
6970 mc .configPeakOutputForward (1 , kTimeout );
7071 mc .configPeakOutputReverse (-1 , kTimeout );
7172 }
73+
74+ /**
75+ * This function takes in a VictorSPX motorController and sets nominal and peak
76+ * outputs to the default
77+ *
78+ * @param mc
79+ * the VictorSPX to configure
80+ */
81+ private void configSPX (WPI_VictorSPX mc ) {
82+ int kTimeout = (int ) Robot .getConst ("kTimeoutMs" , 10 );
83+ mc .configNominalOutputForward (0 , kTimeout );
84+ mc .configNominalOutputReverse (0 , kTimeout );
85+ mc .configPeakOutputForward (1 , kTimeout );
86+ mc .configPeakOutputReverse (-1 , kTimeout );
87+ }
7288
7389 public RobotMap () {
7490
7591 leftEnc = new Encoder (getPort ("1LeftEnc" , 0 ), getPort ("2LeftEnc" , 1 ));
7692 dtLeftDrive = new WPI_TalonSRX (getPort ("LeftTalonSRXDrive" , 0 ));
7793 configSRX (dtLeftDrive );
78- dtLeftSlave = new WPI_TalonSRX (getPort ("LeftTalonSRXSlave " , 1 ));
79- configSRX (dtLeftSlave );
94+ dtLeftSlave = new WPI_VictorSPX (getPort ("LeftTalonSPXSlave " , 1 ));
95+ configSPX (dtLeftSlave );
8096 dtLeft = new SpeedControllerGroup (dtLeftDrive , dtLeftSlave );
8197
8298 rightEnc = new Encoder (getPort ("1RightEnc" , 2 ), getPort ("2RightEnc" , 3 ));
8399 dtRightDrive = new WPI_TalonSRX (getPort ("RightTalonSRXDrive" , 2 ));
84100 configSRX (dtRightDrive );
85- dtRightSlave = new WPI_TalonSRX (getPort ("RightTalonSRXSlave " , 3 ));
86- configSRX (dtRightSlave );
101+ dtRightSlave = new WPI_VictorSPX (getPort ("RightTalonSPXSlave " , 3 ));
102+ configSPX (dtRightSlave );
87103 dtRight = new SpeedControllerGroup (dtRightDrive , dtRightSlave );
88104
89105 robotDrive = new DifferentialDrive (dtLeft , dtRight );
0 commit comments