finish transferring code
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / DriveDistance.java
CommitLineData
aa160dfd
ME
1package org.usfirst.frc.team3501.robot.commands.driving;
2
9b35aa55 3import org.usfirst.frc.team3501.robot.MathLib;
aa160dfd 4import org.usfirst.frc.team3501.robot.Robot;
e12d6901
CZ
5import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
6import org.usfirst.frc.team3501.robot.utils.PIDController;
aa160dfd 7
e12d6901 8import edu.wpi.first.wpilibj.Preferences;
aa160dfd
ME
9import edu.wpi.first.wpilibj.command.Command;
10
11/**
c0e9f911
ME
12 * This command makes the robot drive a specified distance using encoders on the
13 * robot and using a feedback loop
aa160dfd 14 *
e12d6901
CZ
15 * parameters: distance the robot will move in inches motorVal: the motor input
16 * to set the motors to
aa160dfd
ME
17 */
18public class DriveDistance extends Command {
e12d6901
CZ
19 private DriveTrain driveTrain = Robot.getDriveTrain();
20 private double maxTimeOut;
21 private PIDController driveController;
22 private PIDController gyroController;
23 private Preferences prefs;
24
25 private double target;
26 private double gyroP;
27 private double gyroI;
28 private double gyroD;
29
30 private double driveP;
31 private double driveI;
32 private double driveD;
aa160dfd 33
8e4c083c 34 public DriveDistance(double distance, double maxTimeOut) {
e12d6901 35 requires(driveTrain);
8e4c083c
CZ
36 this.maxTimeOut = maxTimeOut;
37 this.target = distance;
38
9b35aa55
CZ
39 private double target;
40 private double gyroP;
41 private double gyroI;
42 private double gyroD;
43
44 private double driveP;
45 private double driveI;
46 private double driveD;
47
48 public DriveDistance(double distance, double motorVal) {
49 requires(driveTrain);
e12d6901
CZ
50 this.driveP = driveTrain.driveP;
51 this.driveI = driveTrain.driveI;
52 this.driveD = driveTrain.driveD;
53 this.gyroP = driveTrain.defaultGyroP;
54 this.gyroI = driveTrain.defaultGyroI;
55 this.gyroD = driveTrain.defaultGyroD;
56 this.driveController = new PIDController(this.driveP, this.driveI,
57 this.driveD);
58 this.driveController.setDoneRange(0.5);
59 this.driveController.setMaxOutput(1.0);
60 this.driveController.setMinDoneCycles(5);
61
62 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
63 this.gyroController.setDoneRange(1);
64 this.gyroController.setMinDoneCycles(5);
d17d868d 65 }
66
d17d868d 67 @Override
68 protected void initialize() {
e12d6901
CZ
69 this.driveTrain.resetEncoders();
70 this.driveTrain.resetGyro();
71 this.driveController.setSetPoint(this.target);
72 this.gyroController.setSetPoint(this.driveTrain.getZeroAngle());
d17d868d 73 }
74
d17d868d 75 @Override
76 protected void execute() {
e12d6901
CZ
77 double xVal = 0;
78 double yVal = this.driveController
79 .calcPID(this.driveTrain.getAvgEncoderDistance());
80
81 if (this.driveTrain.getAngle() - this.driveTrain.getZeroAngle() < 30) {
82 xVal = -this.gyroController
83 .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
84 }
8e4c083c
CZ
85 double leftDrive = yVal - xVal;
86 double rightDrive = yVal + xVal;
e12d6901
CZ
87
88 this.driveTrain.setMotorValues(leftDrive, rightDrive);
89
8e4c083c 90 driveTrain.printEncoderOutput();
9b35aa55
CZ
91 // System.out.println("turn: " + xVal);
92 double leftDrive = MathLib.calcLeftTankDrive(-xVal, yVal);
93 double rightDrive = MathLib.calcRightTankDrive(xVal, -yVal);
94
95 this.driveTrain.setMotorValues(leftDrive, rightDrive);
96
97 System.out.println(driveTrain.getAvgEncoderDistance());
98 // System.out.println("motorval: " + yVal);
d17d868d 99 }
100
d17d868d 101 @Override
102 protected boolean isFinished() {
e12d6901
CZ
103 boolean isDone = this.driveController.isDone();
104 if (timeSinceInitialized() >= maxTimeOut || isDone)
105 System.out.println("time: " + timeSinceInitialized());
106 return timeSinceInitialized() >= maxTimeOut || isDone;
d17d868d 107 }
108
d17d868d 109 @Override
110 protected void end() {
e12d6901 111 driveTrain.stop();
d17d868d 112 }
113
d17d868d 114 @Override
115 protected void interrupted() {
e12d6901 116 end();
d17d868d 117 }
aa160dfd 118}