Add command group for ToggleWinch
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 645e345b54a692f62d154141a6b2c64e8a0b7556..7463b8685faa504319777e830231c066b8088154 100644 (file)
@@ -14,9 +14,8 @@ 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;
@@ -33,6 +32,9 @@ public class DriveTrain extends Subsystem {
 
   private ADXRS450_Gyro imu;
 
+  private boolean isClimbing;
+  private static double CLIMBER_SPEED;;
+
   private DriveTrain() {
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -61,6 +63,8 @@ public class DriveTrain extends Subsystem {
     rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
         Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
         Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
+
+    CLIMBER_SPEED = Constants.DriveTrain.CLIMBER_SPEED;
   }
 
   public static DriveTrain getDriveTrain() {
@@ -77,6 +81,7 @@ public class DriveTrain extends Subsystem {
 
     frontRight.set(-right);
     rearRight.set(-right);
+    this.isClimbing = true;
   }
 
   public void joystickDrive(final double thrust, final double twist) {
@@ -85,6 +90,7 @@ public class DriveTrain extends Subsystem {
 
   public void stop() {
     setMotorValues(0, 0);
+    this.isClimbing = false;
   }
 
   public double getLeftMotorVal() {
@@ -106,11 +112,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() {
@@ -136,17 +140,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
@@ -190,4 +190,16 @@ public class DriveTrain extends Subsystem {
     setDefaultCommand(new JoystickDrive());
   }
 
+  public boolean isClimbing() {
+    return this.isClimbing;
+  }
+
+  public void setClimbing(boolean isClimbing) {
+    this.isClimbing = isClimbing;
+  }
+
+  public double getClimbingSpeed() {
+    return this.CLIMBER_SPEED;
+  }
+
 }