@@ -55,6 +55,13 @@ public class RobotMap {
5555 public static AnalogGyro dtGyro ;
5656 public static DoubleSolenoid dtGear ;
5757
58+ /**
59+ * This function takes in a TalonSRX motorController and sets nominal and peak
60+ * outputs to the default
61+ *
62+ * @param mc
63+ * the TalonSRX to configure
64+ */
5865 private void configSRX (WPI_TalonSRX mc ) {
5966 int kTimeout = (int ) Robot .getConst ("kTimeoutMs" , 10 );
6067 mc .configNominalOutputForward (0 , kTimeout );
@@ -66,7 +73,7 @@ private void configSRX(WPI_TalonSRX mc) {
6673 public RobotMap () {
6774
6875 leftEnc = new Encoder (getPort ("1LeftEnc" , 0 ), getPort ("2LeftEnc" , 1 ));
69- dtLeftDrive = new WPI_TalonSRX (getPort ("LeftTalonSRXDrive" , 1 ));
76+ dtLeftDrive = new WPI_TalonSRX (getPort ("LeftTalonSRXDrive" , 0 ));
7077 configSRX (dtLeftDrive );
7178 dtLeftSlave = new WPI_TalonSRX (getPort ("LeftTalonSRXSlave" , 1 ));
7279 configSRX (dtLeftSlave );
@@ -75,7 +82,7 @@ public RobotMap() {
7582 rightEnc = new Encoder (getPort ("1RightEnc" , 2 ), getPort ("2RightEnc" , 3 ));
7683 dtRightDrive = new WPI_TalonSRX (getPort ("RightTalonSRXDrive" , 2 ));
7784 configSRX (dtRightDrive );
78- dtRightSlave = new WPI_TalonSRX (getPort ("RightTalonSRXSlave" , 1 ));
85+ dtRightSlave = new WPI_TalonSRX (getPort ("RightTalonSRXSlave" , 3 ));
7986 configSRX (dtRightSlave );
8087 dtRight = new SpeedControllerGroup (dtRightDrive , dtRightSlave );
8188
@@ -130,7 +137,7 @@ public RobotMap() {
130137 * @return returns the Port
131138 */
132139 public int getPort (String key , int def ) {
133- if (!SmartDashboard .containsKey (key )) {
140+ if (!SmartDashboard .containsKey ("Port/" + key )) {
134141 SmartDashboard .putNumber ("Port/" + key , def );
135142 }
136143 return (int ) SmartDashboard .getNumber ("Port/" + key , def );
0 commit comments