Delete PID stuff that somehow got into master
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 2bb3c7a65422789fdacec52f957313b752a510c1..6969ed1d961de1130ef7f9658578a770b4a09662 100644 (file)
@@ -12,17 +12,6 @@ public class DriveTrain extends Subsystem {
   private Encoder leftEncoder, rightEncoder;
   private CANTalon frontLeft, frontRight, rearLeft, rearRight;
 
-  // Drivetrain specific constants that relate to the inches per pulse value for
-  // the encoders
-  private final static double WHEEL_DIAMETER = 6.0; // in inches
-  private final static double PULSES_PER_ROTATION = 256; // in pulses
-  private final static double OUTPUT_SPROCKET_DIAMETER = 2.0; // in inches
-  private final static double WHEEL_SPROCKET_DIAMETER = 3.5; // in inches
-
-  public final static double INCHES_PER_PULSE = (((Math.PI)
-      * OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION) / WHEEL_SPROCKET_DIAMETER)
-      * WHEEL_DIAMETER;
-
   public DriveTrain() {
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
     frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
@@ -33,8 +22,8 @@ public class DriveTrain extends Subsystem {
         Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
     rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
         Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X);
-    leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
-    rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
+    leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
+    rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
   }
 
   @Override
@@ -82,5 +71,4 @@ public class DriveTrain extends Subsystem {
     this.rearLeft.set(leftSpeed);
     this.rearRight.set(-rightSpeed);
   }
-
 }