competition fixes
[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
CZ
24
25 private double driveP;
26 private double driveI;
27 private double driveD;
35527abe 28 private double gyroP;
aa160dfd 29
db326f40 30 public DriveDistance(double distance, double maxTimeOut) {
9b35aa55 31 requires(driveTrain);
174f415c
CZ
32 this.maxTimeOut = maxTimeOut;
33 this.target = distance;
34
e12d6901
CZ
35 this.driveP = driveTrain.driveP;
36 this.driveI = driveTrain.driveI;
37 this.driveD = driveTrain.driveD;
35527abe
CZ
38 this.gyroP = driveTrain.driveStraightGyroP;
39 this.driveController = new PIDController(driveP, driveI, driveD);
c726d04a 40 this.driveController.setDoneRange(1.0);
e12d6901
CZ
41 this.driveController.setMaxOutput(1.0);
42 this.driveController.setMinDoneCycles(5);
d17d868d 43 }
44
d17d868d 45 @Override
46 protected void initialize() {
e12d6901 47 this.driveTrain.resetEncoders();
e12d6901 48 this.driveController.setSetPoint(this.target);
c726d04a 49 this.zeroAngle = driveTrain.getAngle();
d17d868d 50 }
51
d17d868d 52 @Override
53 protected void execute() {
35527abe 54 double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
9ca89e45 55 double yVal = driveController.calcPID(driveTrain.getRightEncoderDistance());
e12d6901 56
8e4c083c
CZ
57 double leftDrive = yVal - xVal;
58 double rightDrive = yVal + xVal;
e12d6901 59 this.driveTrain.setMotorValues(leftDrive, rightDrive);
d17d868d 60 }
61
d17d868d 62 @Override
63 protected boolean isFinished() {
35527abe
CZ
64 return timeSinceInitialized() >= maxTimeOut
65 || this.driveController.isDone();
d17d868d 66 }
67
d17d868d 68 @Override
69 protected void end() {
70 }
71
d17d868d 72 @Override
73 protected void interrupted() {
e12d6901 74 end();
d17d868d 75 }
aa160dfd 76}