Delete PID stuff that somehow got into master
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 4a6c6890d6d031683e2b37d4df4f4a19f5a7a96c..6969ed1d961de1130ef7f9658578a770b4a09662 100644 (file)
@@ -8,20 +8,9 @@ import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class DriveTrain extends Subsystem {
-  // Drivetrain Related Objects
-  private CANTalon frontLeft, frontRight, rearLeft, rearRight;
+  // Drivetrain related objects
   private Encoder leftEncoder, rightEncoder;
-
-  // Drivetrain Specific Constants that relate to the Inches per Pulse value of
-  // 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;
+  private CANTalon frontLeft, frontRight, rearLeft, rearRight;
 
   public DriveTrain() {
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -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
@@ -75,12 +64,11 @@ public class DriveTrain extends Subsystem {
   }
 
   public void setMotorSpeeds(double leftSpeed, double rightSpeed) {
-    // Right motors receive negative values because they turn in the opposite
-    // direction
+    // speed passed to right motor is negative because right motor rotates in
+    // opposite direction
     this.frontLeft.set(leftSpeed);
     this.frontRight.set(-rightSpeed);
     this.rearLeft.set(leftSpeed);
     this.rearRight.set(-rightSpeed);
   }
-
 }