fix bugs
[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 PIDController driveController;
21 private PIDController gyroController;
22 private Preferences prefs;
23
24 private double target;
25 private double gyroP;
26 private double gyroI;
27 private double gyroD;
28
29 private double driveP;
30 private double driveI;
31 private double driveD;
32
33 public DriveDistance(double distance, double maxTimeOut) {
34 requires(driveTrain);
35 this.maxTimeOut = maxTimeOut;
36 this.target = distance;
37
38 private double target;
39 private double gyroP;
40 private double gyroI;
41 private double gyroD;
42
43 private double driveP;
44 private double driveI;
45 private double driveD;
46
47 public DriveDistance(double distance, double motorVal) {
48 requires(driveTrain);
49 this.maxTimeOut = maxTimeOut;
50 this.target = distance;
51
52 this.driveP = driveTrain.driveP;
53 this.driveI = driveTrain.driveI;
54 this.driveD = driveTrain.driveD;
55 this.gyroP = driveTrain.defaultGyroP;
56 this.gyroI = driveTrain.defaultGyroI;
57 this.gyroD = driveTrain.defaultGyroD;
58 this.driveController = new PIDController(this.driveP, this.driveI,
59 this.driveD);
60 this.driveController.setDoneRange(0.5);
61 this.driveController.setMaxOutput(1.0);
62 this.driveController.setMinDoneCycles(5);
63
64 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
65 this.gyroController.setDoneRange(1);
66 this.gyroController.setMinDoneCycles(5);
67 }
68
69 @Override
70 protected void initialize() {
71 this.driveTrain.resetEncoders();
72 this.driveTrain.resetGyro();
73 this.driveController.setSetPoint(this.target);
74 this.gyroController.setSetPoint(this.driveTrain.getZeroAngle());
75 }
76
77 @Override
78 protected void execute() {
79 double xVal = 0;
80 double yVal = this.driveController
81 .calcPID(this.driveTrain.getAvgEncoderDistance());
82
83 if (this.driveTrain.getAngle() - this.driveTrain.getZeroAngle() < 30) {
84 xVal = -this.gyroController
85 .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
86 }
87 double leftDrive = yVal - xVal;
88 double rightDrive = yVal + xVal;
89
90 this.driveTrain.setMotorValues(leftDrive, rightDrive);
91
92 driveTrain.printEncoderOutput();
93 // System.out.println("turn: " + xVal);
94 double leftDrive = yVal - xVal;
95 double rightDrive = yVal + xVal;
96
97 this.driveTrain.setMotorValues(leftDrive, rightDrive);
98
99 driveTrain.printEncoderOutput();
100 // System.out.println("motorval: " + yVal);
101 }
102
103 @Override
104 protected boolean isFinished() {
105 boolean isDone = this.driveController.isDone();
106 if (timeSinceInitialized() >= maxTimeOut || isDone)
107 System.out.println("time: " + timeSinceInitialized());
108 return timeSinceInitialized() >= maxTimeOut || isDone;
109 }
110
111 @Override
112 protected void end() {
113 driveTrain.stop();
114 }
115
116 @Override
117 protected void interrupted() {
118 end();
119 }
120 }