fix stuff
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / DriveDistance.java
1 package org.usfirst.frc.team3501.robot.commands.driving;
2
3 import org.usfirst.frc.team3501.robot.Robot;
4 import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
5 import org.usfirst.frc.team3501.robot.utils.PIDController;
6
7 import edu.wpi.first.wpilibj.Preferences;
8 import edu.wpi.first.wpilibj.command.Command;
9
10 /**
11 * This command makes the robot drive a specified distance using encoders on the
12 * robot and using a feedback loop
13 *
14 * parameters: distance the robot will move in inches motorVal: the motor input
15 * to set the motors to
16 */
17 public class DriveDistance extends Command {
18 private DriveTrain driveTrain = Robot.getDriveTrain();
19 private double maxTimeOut;
20 private double target;
21 private double zeroAngle;
22 private Preferences prefs;
23 private PIDController driveController;
24
25 private double driveP;
26 private double driveI;
27 private double driveD;
28 private double gyroP;
29
30 public DriveDistance(double distance, double maxTimeOut) {
31 requires(driveTrain);
32 this.maxTimeOut = maxTimeOut;
33 this.target = distance;
34
35 this.driveP = driveTrain.driveP;
36 this.driveI = driveTrain.driveI;
37 this.driveD = driveTrain.driveD;
38 this.gyroP = driveTrain.driveStraightGyroP;
39 this.driveController = new PIDController(driveP, driveI, driveD);
40 this.driveController.setDoneRange(1.0);
41 this.driveController.setMaxOutput(1.0);
42 this.driveController.setMinDoneCycles(5);
43 }
44
45 @Override
46 protected void initialize() {
47 this.driveTrain.resetEncoders();
48 this.driveController.setSetPoint(this.target);
49 this.zeroAngle = driveTrain.getAngle();
50 System.out.println("drive " + target);
51 }
52
53 @Override
54 protected void execute() {
55 double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
56 double yVal = driveController.calcPID(driveTrain.getLeftEncoderDistance());
57
58 double leftDrive = yVal - xVal;
59 double rightDrive = yVal + xVal;
60 this.driveTrain.setMotorValues(leftDrive, rightDrive);
61 }
62
63 @Override
64 protected boolean isFinished() {
65 return timeSinceInitialized() >= maxTimeOut
66 || this.driveController.isDone();
67 }
68
69 @Override
70 protected void end() {
71 }
72
73 @Override
74 protected void interrupted() {
75 end();
76 }
77 }