input correct constructor
[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 gyroP;
26
27 public DriveDistance(double distance, double maxTimeOut) {
28 requires(driveTrain);
29 this.maxTimeOut = maxTimeOut;
30 this.target = distance;
31
32 this.driveP = driveTrain.driveP;
33 this.driveI = driveTrain.driveI;
34 this.driveD = driveTrain.driveD;
35 this.gyroP = driveTrain.driveStraightGyroP;
36
37 this.driveController = driveTrain.getDriveController();
38 this.driveController.setDoneRange(0.5);
39 this.driveController.setMaxOutput(1.0);
40 this.driveController.setMinDoneCycles(5);
41 }
42
43 @Override
44 protected void initialize() {
45 this.driveTrain.resetEncoders();
46 this.driveController.setSetPoint(this.target);
47 }
48
49 @Override
50 protected void execute() {
51 double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
52 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
53
54 double leftDrive = yVal - xVal;
55 double rightDrive = yVal + xVal;
56 this.driveTrain.setMotorValues(leftDrive, rightDrive);
57 }
58
59 @Override
60 protected boolean isFinished() {
61 return timeSinceInitialized() >= maxTimeOut
62 || this.driveController.isDone();
63 }
64
65 @Override
66 protected void end() {
67 }
68
69 @Override
70 protected void interrupted() {
71 end();
72 }
73 }