47fc46ea0303ed6689b3c2a03b6c918b30407c8f
[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.MathLib;
4 import org.usfirst.frc.team3501.robot.Robot;
5 import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
6 import org.usfirst.frc.team3501.robot.utils.PIDController;
7
8 import edu.wpi.first.wpilibj.Preferences;
9 import edu.wpi.first.wpilibj.command.Command;
10
11 /**
12 * This command makes the robot drive a specified distance using encoders on the
13 * robot and using a feedback loop
14 *
15 * parameters: distance the robot will move in inches motorVal: the motor input
16 * to set the motors to
17 */
18 public class DriveDistance extends Command {
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;
33
34 public DriveDistance(double distance, double motorVal) {
35 requires(driveTrain);
36 this.driveP = driveTrain.driveP;
37 this.driveI = driveTrain.driveI;
38 this.driveD = driveTrain.driveD;
39 this.gyroP = driveTrain.defaultGyroP;
40 this.gyroI = driveTrain.defaultGyroI;
41 this.gyroD = driveTrain.defaultGyroD;
42 this.driveController = new PIDController(this.driveP, this.driveI,
43 this.driveD);
44 this.driveController.setDoneRange(0.5);
45 this.driveController.setMaxOutput(1.0);
46 this.driveController.setMinDoneCycles(5);
47
48 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
49 this.gyroController.setDoneRange(1);
50 this.gyroController.setMinDoneCycles(5);
51 }
52
53 @Override
54 protected void initialize() {
55 this.driveTrain.resetEncoders();
56 this.driveTrain.resetGyro();
57 this.driveController.setSetPoint(this.target);
58 this.gyroController.setSetPoint(this.driveTrain.getZeroAngle());
59 }
60
61 @Override
62 protected void execute() {
63 double xVal = 0;
64 double yVal = this.driveController
65 .calcPID(this.driveTrain.getAvgEncoderDistance());
66
67 if (this.driveTrain.getAngle() - this.driveTrain.getZeroAngle() < 30) {
68 xVal = -this.gyroController
69 .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
70 }
71 // System.out.println("turn: " + xVal);
72 double leftDrive = MathLib.calcLeftTankDrive(-xVal, yVal);
73 double rightDrive = MathLib.calcRightTankDrive(xVal, -yVal);
74
75 this.driveTrain.setMotorValues(leftDrive, rightDrive);
76
77 System.out.println(driveTrain.getAvgEncoderDistance());
78 // System.out.println("motorval: " + yVal);
79 }
80
81 @Override
82 protected boolean isFinished() {
83 boolean isDone = this.driveController.isDone();
84 if (timeSinceInitialized() >= maxTimeOut || isDone)
85 System.out.println("time: " + timeSinceInitialized());
86 return timeSinceInitialized() >= maxTimeOut || isDone;
87 }
88
89 @Override
90 protected void end() {
91 driveTrain.stop();
92 }
93
94 @Override
95 protected void interrupted() {
96 end();
97 }
98 }