move pidcontroller into drivetrain
[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
10 /**
11 * This command makes the robot drive a specified distance using encoders on the
12 * robot and using a feedback loop
13 *
14 * parameters: distance the robot will move in inches motorVal: the motor input
15 * to set the motors to
16 */
17 public class DriveDistance extends Command {
18 private DriveTrain driveTrain = Robot.getDriveTrain();
19 private double maxTimeOut;
20 private double target;
21 private double zeroAngle;
22 private Preferences prefs;
23 private PIDController driveController;
24
25 private double gyroP;
26
27 public DriveDistance(double distance, double maxTimeOut) {
28 requires(driveTrain);
29 this.maxTimeOut = maxTimeOut;
30 this.target = distance;
31
32 this.gyroP = driveTrain.getGyroController().getP();
33
34 this.driveController = driveTrain.getDriveController();
35 this.driveController.setDoneRange(0.5);
36 this.driveController.setMaxOutput(1.0);
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 = gyroP * (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
56 @Override
57 protected boolean isFinished() {
58 return timeSinceInitialized() >= maxTimeOut
59 || this.driveController.isDone();
60 }
61
62 @Override
63 protected void end() {
64 }
65
66 @Override
67 protected void interrupted() {
68 end();
69 }
70 }