98628f34c9df8260dafcaab43d51dd05aa1d7508
[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 double target;
21 private double zeroAngle;
22 private Preferences prefs;
23 private PIDController driveController;
24
25 private double gyroP;
26
27 public DriveDistance(double distance, double maxTimeOut) {
28 requires(driveTrain);
29 this.maxTimeOut = maxTimeOut;
30 this.target = distance;
31
32 this.driveController = driveTrain.getDriveController();
33 this.driveController.setDoneRange(0.5);
34 this.driveController.setMaxOutput(1.0);
35 this.driveController.setMinDoneCycles(5);
36 }
37
38 @Override
39 protected void initialize() {
40 this.driveTrain.resetEncoders();
41 this.driveController.setSetPoint(this.target);
42 this.zeroAngle = driveTrain.getAngle();
43 }
44
45 @Override
46 protected void execute() {
47 double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
48 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
49
50 double leftDrive = yVal - xVal;
51 double rightDrive = yVal + xVal;
52 this.driveTrain.setMotorValues(leftDrive, rightDrive);
53 }
54
55 @Override
56 protected boolean isFinished() {
57 return timeSinceInitialized() >= maxTimeOut
58 || this.driveController.isDone();
59 }
60
61 @Override
62 protected void end() {
63 }
64
65 @Override
66 protected void interrupted() {
67 end();
68 }
69 }