code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / TurnForAngle.java
index 86176f15fe9e3b03ebaf0ac447af00f597f1cb17..b95c8223a69fccad10d0f3d3cc2bc882129bb6ed 100755 (executable)
@@ -28,15 +28,23 @@ public class TurnForAngle extends Command {
   private double gyroI;
   private double gyroD;
 
+  private double zeroAngle;
+
   public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
     requires(Robot.getDriveTrain());
     this.direction = direction;
     this.maxTimeOut = maxTimeOut;
-    this.target = angle;
+    this.target = Math.abs(angle);
 
-    this.gyroP = driveTrain.defaultGyroP;
-    this.gyroI = driveTrain.defaultGyroI;
-    this.gyroD = driveTrain.defaultGyroD;
+    if (angle > 90) {
+      this.gyroP = driveTrain.largeTurnP;
+      this.gyroI = driveTrain.largeTurnI;
+      this.gyroD = driveTrain.largeTurnD;
+    } else {
+      this.gyroP = driveTrain.smallTurnP;
+      this.gyroI = driveTrain.smallTurnI;
+      this.gyroD = driveTrain.smallTurnD;
+    }
 
     this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
     this.gyroController.setDoneRange(1);
@@ -46,8 +54,8 @@ public class TurnForAngle extends Command {
   @Override
   protected void initialize() {
     this.driveTrain.resetEncoders();
-    this.driveTrain.resetGyro();
     this.gyroController.setSetPoint(this.target);
+    this.zeroAngle = driveTrain.getAngle();
   }
 
   @Override
@@ -55,14 +63,14 @@ public class TurnForAngle extends Command {
     double xVal = 0;
 
     xVal = this.gyroController
-        .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
+        .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle));
 
-    double leftDrive;
-    double rightDrive;
+    double leftDrive = 0;
+    double rightDrive = 0;
     if (direction == Constants.Direction.RIGHT) {
       leftDrive = xVal;
       rightDrive = -xVal;
-    } else {
+    } else if (direction == Constants.Direction.LEFT) {
       leftDrive = -xVal;
       rightDrive = xVal;
     }