cb8227f16017bdde5ef8c0c04c54ed645faad3a6
[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 = 10;
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 driveStraightGyroP = SmartDashboard.getNumber(driveTrain.DRIVE_GYRO_P_Val,
32 driveTrain.PID_ERROR);
33
34 this.driveController = driveTrain.getDriveController();
35 this.driveController.setDoneRange(0.5);
36 this.driveController.setMaxOutput(1.1);
37 this.driveController.setMinDoneCycles(5);
38 }
39
40 @Override
41 protected void initialize() {
42 this.driveTrain.resetEncoders();
43 this.driveController.setSetPoint(this.target);
44 }
45
46 @Override
47 protected void execute() {
48 double xVal = driveStraightGyroP * (driveTrain.getAngle() - zeroAngle);
49 double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
50
51 double leftDrive = yVal - xVal;
52 double rightDrive = yVal + xVal;
53 this.driveTrain.setMotorValues(leftDrive, rightDrive);
54
55 System.out.println(
56 "PID VALS: " + driveController.getP() + " " + driveController.getI()
57 + " " + driveController.getD());
58
59 System.out.println(driveTrain.getAvgEncoderDistance());
60 }
61
62 @Override
63 protected boolean isFinished() {
64 return timeSinceInitialized() >= maxTimeOut
65 || this.driveController.isDone();
66 }
67
68 @Override
69 protected void end() {
70 }
71
72 @Override
73 protected void interrupted() {
74 end();
75 }
76 }