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