finish implement driveDistance and TurnForAngle using PID algorithm
[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;
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;
aa160dfd 32
8e4c083c 33 public DriveDistance(double distance, double maxTimeOut) {
e12d6901 34 requires(driveTrain);
8e4c083c
CZ
35 this.maxTimeOut = maxTimeOut;
36 this.target = distance;
37
e12d6901
CZ
38 this.driveP = driveTrain.driveP;
39 this.driveI = driveTrain.driveI;
40 this.driveD = driveTrain.driveD;
41 this.gyroP = driveTrain.defaultGyroP;
42 this.gyroI = driveTrain.defaultGyroI;
43 this.gyroD = driveTrain.defaultGyroD;
44 this.driveController = new PIDController(this.driveP, this.driveI,
45 this.driveD);
46 this.driveController.setDoneRange(0.5);
47 this.driveController.setMaxOutput(1.0);
48 this.driveController.setMinDoneCycles(5);
49
50 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
51 this.gyroController.setDoneRange(1);
52 this.gyroController.setMinDoneCycles(5);
d17d868d 53 }
54
d17d868d 55 @Override
56 protected void initialize() {
e12d6901
CZ
57 this.driveTrain.resetEncoders();
58 this.driveTrain.resetGyro();
59 this.driveController.setSetPoint(this.target);
60 this.gyroController.setSetPoint(this.driveTrain.getZeroAngle());
d17d868d 61 }
62
d17d868d 63 @Override
64 protected void execute() {
e12d6901
CZ
65 double xVal = 0;
66 double yVal = this.driveController
67 .calcPID(this.driveTrain.getAvgEncoderDistance());
68
69 if (this.driveTrain.getAngle() - this.driveTrain.getZeroAngle() < 30) {
70 xVal = -this.gyroController
71 .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
72 }
8e4c083c
CZ
73 double leftDrive = yVal - xVal;
74 double rightDrive = yVal + xVal;
e12d6901
CZ
75
76 this.driveTrain.setMotorValues(leftDrive, rightDrive);
77
8e4c083c 78 driveTrain.printEncoderOutput();
d17d868d 79 }
80
d17d868d 81 @Override
82 protected boolean isFinished() {
e12d6901
CZ
83 boolean isDone = this.driveController.isDone();
84 if (timeSinceInitialized() >= maxTimeOut || isDone)
85 System.out.println("time: " + timeSinceInitialized());
86 return timeSinceInitialized() >= maxTimeOut || isDone;
d17d868d 87 }
88
d17d868d 89 @Override
90 protected void end() {
e12d6901 91 driveTrain.stop();
d17d868d 92 }
93
d17d868d 94 @Override
95 protected void interrupted() {
e12d6901 96 end();
d17d868d 97 }
aa160dfd 98}