update code
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 645e345b54a692f62d154141a6b2c64e8a0b7556..83f48d50d650ee0de3e95ac40dbee35e222c4e74 100644 (file)
@@ -2,6 +2,7 @@ package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
 
 import com.ctre.CANTalon;
 
@@ -13,17 +14,20 @@ import edu.wpi.first.wpilibj.RobotDrive;
 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 driveP, driveI, driveD;
+  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;
+
+  public static final double MAINTAIN_CLIMBED_POSITION = 0;
+  public static final double TIME_TO_CLIMB_FOR = 0;
+  public static final double CLIMBER_SPEED = 0;
+
   private static DriveTrain driveTrain;
 
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
@@ -33,7 +37,14 @@ public class DriveTrain extends Subsystem {
 
   private ADXRS450_Gyro imu;
 
+  public boolean shouldBeClimbing = false;
+
+  private PIDController driveController;
+
   private DriveTrain() {
+
+    driveController = new PIDController(driveP, driveI, driveD);
+
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
     frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
@@ -55,14 +66,18 @@ public class DriveTrain extends Subsystem {
     this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
 
     // TODO: Not sure if MODULE_NUMBER should be the same for both
-    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
+    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
         Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
         Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
-    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
+    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
         Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
         Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
   }
 
+  public PIDController getDriveController() {
+    return this.driveController;
+  }
+
   public static DriveTrain getDriveTrain() {
     if (driveTrain == null) {
       driveTrain = new DriveTrain();
@@ -106,11 +121,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 +149,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
@@ -189,5 +198,4 @@ public class DriveTrain extends Subsystem {
   protected void initDefaultCommand() {
     setDefaultCommand(new JoystickDrive());
   }
-
 }