code review changes and add code for braking cantalons
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 7784854220a2994b4134c2bc9bb5c1bc624fc7bc..bad303aebe622f0db77aa8a41d45e79b92c68325 100644 (file)
@@ -1,6 +1,7 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
 
 import com.ctre.CANTalon;
@@ -13,17 +14,26 @@ 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 final double WHEEL_DIAMETER = 6; // inches
-  public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
+  public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002;
+  public static double smallTurnP = 0.004, smallTurnI = 0.0013,
+      smallTurnD = 0.005;
+  public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
+  public static double driveStraightGyroP = 0.01;
+
+  public static final double WHEEL_DIAMETER = 4; // inches
+  public static final double ENCODER_PULSES_PER_REVOLUTION = 256;
   public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
       / ENCODER_PULSES_PER_REVOLUTION;
 
+  public static final double MAINTAIN_CLIMBED_POSITION = 0;
+  public static final double TIME_TO_CLIMB_FOR = 0;
+  public static final double CLIMBER_SPEED = 0;
+
+  public static final boolean DRIVE_BRAKE_MODE = true;
+  public static final boolean DRIVE_COAST_MODE = false;
+
   private static DriveTrain driveTrain;
+
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private final RobotDrive robotDrive;
   private final Encoder leftEncoder, rightEncoder;
@@ -31,6 +41,8 @@ public class DriveTrain extends Subsystem {
 
   private ADXRS450_Gyro imu;
 
+  public boolean shouldBeClimbing = false;
+
   private DriveTrain() {
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -52,10 +64,13 @@ public class DriveTrain extends Subsystem {
 
     this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
 
-    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
-        Constants.DriveTrain.LEFT_FORWARD, Constants.DriveTrain.LEFT_REVERSE);
-    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER,
-        Constants.DriveTrain.RIGHT_FORWARD, Constants.DriveTrain.RIGHT_REVERSE);
+    // TODO: Not sure if MODULE_NUMBER should be the same for both
+    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
+        Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
+        Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
+    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE,
+        Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
+        Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
   }
 
   public static DriveTrain getDriveTrain() {
@@ -66,7 +81,10 @@ public class DriveTrain extends Subsystem {
   }
 
   // DRIVE METHODS
-  public void setMotorValues(final double left, final double right) {
+  public void setMotorValues(double left, double right) {
+    left = MathLib.restrictToRange(left, -1.0, 1.0);
+    right = MathLib.restrictToRange(right, -1.0, 1.0);
+
     frontLeft.set(left);
     rearLeft.set(left);
 
@@ -101,11 +119,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() {
@@ -131,17 +147,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
@@ -185,4 +197,11 @@ public class DriveTrain extends Subsystem {
     setDefaultCommand(new JoystickDrive());
   }
 
+  public void setCANTalonsBrakeMode(boolean mode) {
+    frontLeft.enableBrakeMode(mode);
+    rearLeft.enableBrakeMode(mode);
+
+    frontRight.enableBrakeMode(mode);
+    rearRight.enableBrakeMode(mode);
+  }
 }