@@ -35,91 +35,104 @@ public class RobotMap {
3535 // number and the module. For example you with a rangefinder:
3636 // public static int rangefinderPort = 1;
3737 // public static int rangefinderModule = 1;
38-
38+
3939 public static Encoder leftEnc ;
4040 public static WPI_TalonSRX dtLeftDrive ;
41- public static WPI_TalonSRX dtLeftSlave ;
41+ public static WPI_TalonSRX dtLeftSlave ;
4242 public static SpeedControllerGroup dtLeft ;
43-
43+
4444 public static Encoder rightEnc ;
4545 public static WPI_TalonSRX dtRightDrive ;
46- public static WPI_TalonSRX dtRightSlave ;
46+ public static WPI_TalonSRX dtRightSlave ;
4747 public static SpeedControllerGroup dtRight ;
4848 public static DifferentialDrive robotDrive ;
4949 public static PIDController turnController ;
5050 public static PIDController moveController ;
51- // public static PIDController moveLeftController;
52- // public static PIDController moveRightController;
53-
51+ // public static PIDController moveLeftController;
52+ // public static PIDController moveRightController;
53+
5454 public static AHRS ahrs ;
5555 public static AnalogGyro dtGyro ;
5656 public static DoubleSolenoid dtGear ;
57-
57+
5858 private void configSRX (WPI_TalonSRX mc ) {
5959 int kTimeout = (int ) Robot .getConst ("ConstkTimeoutMs" , 10 );
6060 mc .configNominalOutputForward (0 , kTimeout );
61- mc .configNominalOutputReverse (0 , kTimeout );
62- mc .configPeakOutputForward (1 , kTimeout );
63- mc .configPeakOutputReverse (-1 , kTimeout );
61+ mc .configNominalOutputReverse (0 , kTimeout );
62+ mc .configPeakOutputForward (1 , kTimeout );
63+ mc .configPeakOutputReverse (-1 , kTimeout );
6464 }
65+
6566 public RobotMap () {
66-
67+
6768 leftEnc = new Encoder (getPort ("Port1LeftEnc" , 0 ), getPort ("Port2LeftEnc" , 1 ));
6869 dtLeftDrive = new WPI_TalonSRX (getPort ("PortLeftTalonSRXDrive" , 1 ));
6970 configSRX (dtLeftDrive );
70- dtLeftSlave = new WPI_TalonSRX (getPort ("PortLeftTalonSRXSlave" , 1 ));
71- configSRX (dtLeftSlave );
71+ dtLeftSlave = new WPI_TalonSRX (getPort ("PortLeftTalonSRXSlave" , 1 ));
72+ configSRX (dtLeftSlave );
7273 dtLeft = new SpeedControllerGroup (dtLeftDrive , dtLeftSlave );
73-
74+
7475 rightEnc = new Encoder (getPort ("Port1RightEnc" , 2 ), getPort ("Port2RightEnc" , 3 ));
7576 dtRightDrive = new WPI_TalonSRX (getPort ("PortRightTalonSRXDrive" , 2 ));
7677 configSRX (dtRightDrive );
77- dtRightSlave = new WPI_TalonSRX (getPort ("PortRightTalonSRXSlave" , 1 ));
78- configSRX (dtRightSlave );
78+ dtRightSlave = new WPI_TalonSRX (getPort ("PortRightTalonSRXSlave" , 1 ));
79+ configSRX (dtRightSlave );
7980 dtRight = new SpeedControllerGroup (dtRightDrive , dtRightSlave );
80-
81+
8182 robotDrive = new DifferentialDrive (dtLeft , dtRight );
82- turnController = new PIDController (Robot .getConst ("ConstTurnkP" , 1 ), Robot .getConst ("ConstTurnkI" , 0 ), Robot .getConst ("ConstTurnkD" , 0 ), ahrs , Robot .dt );
83- turnController .disable ();
84- turnController .setInputRange (-180 , 180 );
85- turnController .setOutputRange (-1.0 , 1.0 );
86- turnController .setContinuous ();
87- turnController .setAbsoluteTolerance (Robot .getConst ("ConstTurnTolerance" , 1 ));
88- moveController = new PIDController (Robot .getConst ("ConstMovekP" , 1 ), Robot .getConst ("ConstMovekI" , 0 ), Robot .getConst ("ConstMovekD" , 0 ), Robot .dt , Robot .dt );
89- turnController .disable ();
90- turnController .setInputRange (-180 , 180 );
91- turnController .setOutputRange (-1.0 , 1.0 );
92- turnController .setContinuous ();
93- turnController .setAbsoluteTolerance (Robot .getConst ("ConstMoveTolerance" , 2 ));
94- // moveLeftController = new PIDController(Robot.getConst("ConstMoveLeftkP", 1), Robot.getConst("ConstMoveLeftkI", 0), Robot.getConst("ConstMoveLeftkD", 0), Robot.dt.getLeftDrive(), (PIDOutput) Robot.dt.getLeftDrive());
95- // moveLeftController.disable();
96- // moveLeftController.setInputRange(0, Double.MAX_VALUE);
97- // moveLeftController.setOutputRange(-1.0, 1.0);
98- // moveLeftController.setContinuous(false);
99- // moveLeftController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceLeft", 2));
100- // moveRightController = new PIDController(Robot.getConst("ConstMoveRightkP", 1), Robot.getConst("ConstMoveRightkI", 0), Robot.getConst("ConstMoveRightkD", 0), Robot.dt.getRightDrive(), (PIDOutput) Robot.dt.getRightDrive());
101- // moveRightController.disable();
102- // moveRightController.setInputRange(0, Double.MAX_VALUE);
103- // moveRightController.setOutputRange(-1.0, 1.0);
104- // moveRightController.setContinuous(false);
105- // moveRightController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight", 2));
106-
83+ turnController = new PIDController (Robot .getConst ("ConstTurnkP" , 1 ), Robot .getConst ("ConstTurnkI" , 0 ),
84+ Robot .getConst ("ConstTurnkD" , 0 ), ahrs , Robot .dt );
85+ turnController .disable ();
86+ turnController .setInputRange (-180 , 180 );
87+ turnController .setOutputRange (-1.0 , 1.0 );
88+ turnController .setContinuous ();
89+ turnController .setAbsoluteTolerance (Robot .getConst ("ConstTurnTolerance" , 1 ));
90+ moveController = new PIDController (Robot .getConst ("ConstMovekP" , 1 ), Robot .getConst ("ConstMovekI" , 0 ),
91+ Robot .getConst ("ConstMovekD" , 0 ), Robot .dt , Robot .dt );
92+ turnController .disable ();
93+ turnController .setInputRange (-180 , 180 );
94+ turnController .setOutputRange (-1.0 , 1.0 );
95+ turnController .setContinuous ();
96+ turnController .setAbsoluteTolerance (Robot .getConst ("ConstMoveTolerance" , 2 ));
97+ // moveLeftController = new PIDController(Robot.getConst("ConstMoveLeftkP", 1),
98+ // Robot.getConst("ConstMoveLeftkI", 0), Robot.getConst("ConstMoveLeftkD", 0),
99+ // Robot.dt.getLeftDrive(), (PIDOutput) Robot.dt.getLeftDrive());
100+ // moveLeftController.disable();
101+ // moveLeftController.setInputRange(0, Double.MAX_VALUE);
102+ // moveLeftController.setOutputRange(-1.0, 1.0);
103+ // moveLeftController.setContinuous(false);
104+ // moveLeftController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceLeft",
105+ // 2));
106+ // moveRightController = new PIDController(Robot.getConst("ConstMoveRightkP",
107+ // 1), Robot.getConst("ConstMoveRightkI", 0), Robot.getConst("ConstMoveRightkD",
108+ // 0), Robot.dt.getRightDrive(), (PIDOutput) Robot.dt.getRightDrive());
109+ // moveRightController.disable();
110+ // moveRightController.setInputRange(0, Double.MAX_VALUE);
111+ // moveRightController.setOutputRange(-1.0, 1.0);
112+ // moveRightController.setContinuous(false);
113+ // moveRightController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight",
114+ // 2));
115+
107116 ahrs = new AHRS (SerialPort .Port .kMXP );
108117 dtGyro = new AnalogGyro (getPort ("PortGyro" , 0 ));
109118 dtGear = new DoubleSolenoid (getPort ("Port1dtGearSolenoid" , 0 ), getPort ("Port2dtGearSolenoid" , 1 ));
110-
119+
111120 }
112-
121+
113122 /**
114- * Used in RobotMap to find ports for robot components, getPort also puts numbers if they don't exist yet.
115- * @param key The port key
116- * @param def The default value
123+ * Used in RobotMap to find ports for robot components, getPort also puts
124+ * numbers if they don't exist yet.
125+ *
126+ * @param key
127+ * The port key
128+ * @param def
129+ * The default value
117130 * @return returns the Port
118131 */
119132 public int getPort (String key , int def ) {
120- if (!SmartDashboard .containsKey (key )) {
133+ if (!SmartDashboard .containsKey (key )) {
121134 SmartDashboard .putNumber (key , def );
122135 }
123- return (int )SmartDashboard .getNumber (key , def );
136+ return (int ) SmartDashboard .getNumber (key , def );
124137 }
125138}
0 commit comments