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();
c9cdc810 20 private double maxTimeOut;
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;
c9cdc810 31 this.maxTimeOut = maxTimeOut;
b5ddf3e2
ES
32 driveStraightGyroP = SmartDashboard.getNumber(driveTrain.DRIVE_GYRO_P_Val,
33 driveTrain.PID_ERROR);
d3ed4499 34
9ffd117a
E
35 this.driveController = driveTrain.getDriveController();
36 this.driveController.setDoneRange(0.5);
c9cdc810 37 this.driveController.setMaxOutput(1.0);
e12d6901 38 this.driveController.setMinDoneCycles(5);
d17d868d 39 }
40
d17d868d 41 @Override
42 protected void initialize() {
e12d6901 43 this.driveTrain.resetEncoders();
e12d6901 44 this.driveController.setSetPoint(this.target);
576421d8 45 zeroAngle = driveTrain.getAngle();
d17d868d 46 }
47
d17d868d 48 @Override
49 protected void execute() {
576421d8 50 System.out.printf("angle: %.2f\t", driveTrain.getAngle() - zeroAngle);
b5ddf3e2 51 double xVal = driveStraightGyroP * (driveTrain.getAngle() - zeroAngle);
35527abe 52 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
e12d6901 53
8e4c083c
CZ
54 double leftDrive = yVal - xVal;
55 double rightDrive = yVal + xVal;
e12d6901 56 this.driveTrain.setMotorValues(leftDrive, rightDrive);
b5ddf3e2 57
576421d8
ES
58 // SmartDashboard.putNumber("x", xVal);
59 // SmartDashboard.putNumber("y", yVal);
60 //
61 // SmartDashboard.putNumber("left", driveTrain.getLeftEncoderDistance());
62 // SmartDashboard.putNumber("right", driveTrain.getRightEncoderDistance());
63 //
64 // System.out.printf("x: %.2f\t", xVal);
65 // System.out.printf("y: %.2f\t", yVal);
66 //
67 // System.out.printf("dist: %.2f\n", driveTrain.getAvgEncoderDistance());
b5ddf3e2 68
d17d868d 69 }
70
d17d868d 71 @Override
72 protected boolean isFinished() {
35527abe
CZ
73 return timeSinceInitialized() >= maxTimeOut
74 || this.driveController.isDone();
d17d868d 75 }
76
d17d868d 77 @Override
78 protected void end() {
79 }
80
d17d868d 81 @Override
82 protected void interrupted() {
e12d6901 83 end();
d17d868d 84 }
aa160dfd 85}