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