change some names
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 54324f050caab86d9ac9870ca11dace772b6a63c..f7c35a9108cdf161ac0c3597bf85ca350e63073d 100644 (file)
@@ -14,16 +14,17 @@ import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class DriveTrain extends Subsystem {
   public static double driveP = 0.006, driveI = 0.001, driveD = -0.002;
-  public static double defaultGyroP = 0.004, defaultGyroI = 0.0013,
-      defaultGyroD = -0.005;
-  private double gyroZero = 0;
+  public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
+  public static double driveStraightGyroP = 0.01;
 
   public static final double WHEEL_DIAMETER = 6; // inches
   public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
   public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
       / ENCODER_PULSES_PER_REVOLUTION;
-
+  public static final int MAINTAIN_CLIMBED_POSITION = 0;
+  public static final int TIME_TO_CLIMB_FOR = 0;
   private static DriveTrain driveTrain;
+
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private final RobotDrive robotDrive;
   private final Encoder leftEncoder, rightEncoder;
@@ -51,12 +52,14 @@ public class DriveTrain extends Subsystem {
     robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
 
     this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
-    shifter = DoubleSolenoid(10, Constants.DriveTrain.SHIFTER_FORWARD,
-        Constants.DriveTrain.SHIFTER_REVERSE);
+
+    // TODO: Not sure if MODULE_NUMBER should be the same for both
     leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
-        Constants.DriveTrain.LEFT_FORWARD, Constants.DriveTrain.LEFT_REVERSE);
+        Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
+        Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
     rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
-        Constants.DriveTrain.RIGHT_FORWARD, Constants.DriveTrain.RIGHT_REVERSE);
+        Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
+        Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
   }
 
   public static DriveTrain getDriveTrain() {
@@ -102,9 +105,9 @@ public class DriveTrain extends Subsystem {
   }
 
   public void printEncoderOutput() {
-    // System.out.println("left: " + getLeftEncoderDistance());
-    // System.out.println("right: " + getRightEncoderDistance());
-    System.out.println(getAvgEncoderDistance());
+    System.out.println("left: " + getLeftEncoderDistance());
+    System.out.println("right: " + getRightEncoderDistance());
+    // System.out.println(getAvgEncoderDistance());
   }
 
   public double getAvgEncoderDistance() {
@@ -130,15 +133,13 @@ public class DriveTrain extends Subsystem {
 
   // ------Gyro------//
   public double getAngle() {
-    return this.imu.getAngle() - this.gyroZero;
+    return this.imu.getAngle();
   }
 
   public void resetGyro() {
     this.imu.reset();
   }
 
-  public double getZeroAngle() {
-    return this.gyroZero;
   /*
    * @return a value that is the current setpoint for the piston kReverse or
    * KForward
@@ -148,8 +149,8 @@ public class DriveTrain extends Subsystem {
   }
 
   /*
-   * @return a value that is the current setppoint for the piston kReverse or
-   * kForward
+   * @return a value that is the current setpoint for the piston kReverse or
+   * KForward
    */
   public Value getRightGearPistonValue() {
     return rightGearPiston.get();