finish implement driveDistance and TurnForAngle using PID algorithm
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / TurnForAngle.java
index 06d14f6c4a1ba407dafb081655f5cba7e2b3545b..86176f15fe9e3b03ebaf0ac447af00f597f1cb17 100755 (executable)
@@ -1,42 +1,86 @@
 package org.usfirst.frc.team3501.robot.commands.driving;
 
+import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.Constants.Direction;
 import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
 
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
+ * This command turns the robot for a specified angle in specified direction -
+ * either left or right
  *
+ * parameters: angle: the robot will turn - in degrees direction: the robot will
+ * turn - either right or left maxTimeOut: the max time this command will be
+ * allowed to run on for
  */
 public class TurnForAngle extends Command {
+  private DriveTrain driveTrain = Robot.getDriveTrain();
 
-    public TurnForAngle() {
-        requires(Robot.getDriveTrain());
-    }
+  Direction direction;
+  private double maxTimeOut;
+  private PIDController gyroController;
 
-    // Called just before this Command runs the first time
-    @Override
-    protected void initialize() {
-    }
+  private double target;
+  private double gyroP;
+  private double gyroI;
+  private double gyroD;
 
-    // Called repeatedly when this Command is scheduled to run
-    @Override
-    protected void execute() {
-    }
+  public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
+    requires(Robot.getDriveTrain());
+    this.direction = direction;
+    this.maxTimeOut = maxTimeOut;
+    this.target = angle;
 
-    // Make this return true when this Command no longer needs to run execute()
-    @Override
-    protected boolean isFinished() {
-        return false;
-    }
+    this.gyroP = driveTrain.defaultGyroP;
+    this.gyroI = driveTrain.defaultGyroI;
+    this.gyroD = driveTrain.defaultGyroD;
 
-    // Called once after isFinished returns true
-    @Override
-    protected void end() {
-    }
+    this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
+    this.gyroController.setDoneRange(1);
+    this.gyroController.setMinDoneCycles(5);
+  }
+
+  @Override
+  protected void initialize() {
+    this.driveTrain.resetEncoders();
+    this.driveTrain.resetGyro();
+    this.gyroController.setSetPoint(this.target);
+  }
 
-    // Called when another command which requires one or more of the same
-    // subsystems is scheduled to run
-    @Override
-    protected void interrupted() {
+  @Override
+  protected void execute() {
+    double xVal = 0;
+
+    xVal = this.gyroController
+        .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
+
+    double leftDrive;
+    double rightDrive;
+    if (direction == Constants.Direction.RIGHT) {
+      leftDrive = xVal;
+      rightDrive = -xVal;
+    } else {
+      leftDrive = -xVal;
+      rightDrive = xVal;
     }
+
+    this.driveTrain.setMotorValues(leftDrive, rightDrive);
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+    end();
+  }
 }