update code
[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 8import edu.wpi.first.wpilibj.command.Command;
b5ddf3e2 9import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
aa160dfd
ME
10
11/**
c0e9f911
ME
12 * This command makes the robot drive a specified distance using encoders on the
13 * robot and using a feedback loop
aa160dfd 14 *
e12d6901
CZ
15 * parameters: distance the robot will move in inches motorVal: the motor input
16 * to set the motors to
aa160dfd
ME
17 */
18public class DriveDistance extends Command {
e12d6901 19 private DriveTrain driveTrain = Robot.getDriveTrain();
a4ea9991 20 private double maxTimeOut = 10;
e12d6901 21 private double target;
35527abe
CZ
22 private double zeroAngle;
23 private Preferences prefs;
24 private PIDController driveController;
e12d6901 25
b5ddf3e2 26 private double driveStraightGyroP;
aa160dfd 27
db326f40 28 public DriveDistance(double distance, double maxTimeOut) {
9b35aa55 29 requires(driveTrain);
174f415c 30 this.target = distance;
b5ddf3e2
ES
31 driveStraightGyroP = SmartDashboard.getNumber(driveTrain.DRIVE_GYRO_P_Val,
32 driveTrain.PID_ERROR);
d3ed4499 33
9ffd117a
E
34 this.driveController = driveTrain.getDriveController();
35 this.driveController.setDoneRange(0.5);
e8b102d5 36 this.driveController.setMaxOutput(1.1);
e12d6901 37 this.driveController.setMinDoneCycles(5);
d17d868d 38 }
39
d17d868d 40 @Override
41 protected void initialize() {
e12d6901 42 this.driveTrain.resetEncoders();
e12d6901 43 this.driveController.setSetPoint(this.target);
d17d868d 44 }
45
d17d868d 46 @Override
47 protected void execute() {
b5ddf3e2 48 double xVal = driveStraightGyroP * (driveTrain.getAngle() - zeroAngle);
35527abe 49 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
e12d6901 50
8e4c083c
CZ
51 double leftDrive = yVal - xVal;
52 double rightDrive = yVal + xVal;
e12d6901 53 this.driveTrain.setMotorValues(leftDrive, rightDrive);
b5ddf3e2
ES
54
55 System.out.println(
56 "PID VALS: " + driveController.getP() + " " + driveController.getI()
57 + " " + driveController.getD());
58
59 System.out.println(driveTrain.getAvgEncoderDistance());
d17d868d 60 }
61
d17d868d 62 @Override
63 protected boolean isFinished() {
35527abe
CZ
64 return timeSinceInitialized() >= maxTimeOut
65 || this.driveController.isDone();
d17d868d 66 }
67
d17d868d 68 @Override
69 protected void end() {
70 }
71
d17d868d 72 @Override
73 protected void interrupted() {
e12d6901 74 end();
d17d868d 75 }
aa160dfd 76}