fix alot of unnecessary/not used code and init gyroController
[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 18 private DriveTrain driveTrain = Robot.getDriveTrain();
a4ea9991 19 private double maxTimeOut = 10;
e12d6901 20 private double target;
35527abe
CZ
21 private double zeroAngle;
22 private Preferences prefs;
23 private PIDController driveController;
e12d6901 24
35527abe 25 private double gyroP;
aa160dfd 26
db326f40 27 public DriveDistance(double distance, double maxTimeOut) {
9b35aa55 28 requires(driveTrain);
174f415c 29 this.target = distance;
d3ed4499 30
9ffd117a
E
31 this.driveController = driveTrain.getDriveController();
32 this.driveController.setDoneRange(0.5);
d3ed4499 33 this.driveController.setMaxOutput(1.1);
e12d6901 34 this.driveController.setMinDoneCycles(5);
d17d868d 35 }
36
d17d868d 37 @Override
38 protected void initialize() {
e12d6901 39 this.driveTrain.resetEncoders();
e12d6901 40 this.driveController.setSetPoint(this.target);
d17d868d 41 }
42
d17d868d 43 @Override
44 protected void execute() {
35527abe
CZ
45 double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
46 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
e12d6901 47
8e4c083c
CZ
48 double leftDrive = yVal - xVal;
49 double rightDrive = yVal + xVal;
e12d6901 50 this.driveTrain.setMotorValues(leftDrive, rightDrive);
d17d868d 51 }
52
d17d868d 53 @Override
54 protected boolean isFinished() {
35527abe
CZ
55 return timeSinceInitialized() >= maxTimeOut
56 || this.driveController.isDone();
d17d868d 57 }
58
d17d868d 59 @Override
60 protected void end() {
61 }
62
d17d868d 63 @Override
64 protected void interrupted() {
e12d6901 65 end();
d17d868d 66 }
aa160dfd 67}