change some names
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / TurnForAngle.java
CommitLineData
aa160dfd
ME
1package org.usfirst.frc.team3501.robot.commands.driving;
2
f0a71840 3import org.usfirst.frc.team3501.robot.Constants;
8af76159 4import org.usfirst.frc.team3501.robot.Constants.Direction;
aa160dfd 5import org.usfirst.frc.team3501.robot.Robot;
f0a71840
CZ
6import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
7import org.usfirst.frc.team3501.robot.utils.PIDController;
aa160dfd
ME
8
9import edu.wpi.first.wpilibj.command.Command;
10
11/**
9b9d6bed
ME
12 * This command turns the robot for a specified angle in specified direction -
13 * either left or right
14 *
f0a71840
CZ
15 * parameters: angle: the robot will turn - in degrees direction: the robot will
16 * turn - either right or left maxTimeOut: the max time this command will be
17 * allowed to run on for
aa160dfd
ME
18 */
19public class TurnForAngle extends Command {
f0a71840 20 private DriveTrain driveTrain = Robot.getDriveTrain();
aa160dfd 21
f0a71840
CZ
22 Direction direction;
23 private double maxTimeOut;
24 private PIDController gyroController;
25
26 private double target;
27 private double gyroP;
28 private double gyroI;
29 private double gyroD;
30
571fb5c9
CZ
31 private double zeroAngle;
32
f0a71840 33 public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
d17d868d 34 requires(Robot.getDriveTrain());
f0a71840
CZ
35 this.direction = direction;
36 this.maxTimeOut = maxTimeOut;
571fb5c9
CZ
37 this.target = Math.abs(angle);
38 this.zeroAngle = driveTrain.getAngle();
f0a71840 39
c846487e
CZ
40 this.gyroP = driveTrain.turnP;
41 this.gyroI = driveTrain.turnI;
42 this.gyroD = driveTrain.turnD;
f0a71840
CZ
43
44 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
45 this.gyroController.setDoneRange(1);
46 this.gyroController.setMinDoneCycles(5);
d17d868d 47 }
48
d17d868d 49 @Override
50 protected void initialize() {
f0a71840 51 this.driveTrain.resetEncoders();
f0a71840 52 this.gyroController.setSetPoint(this.target);
d17d868d 53 }
54
d17d868d 55 @Override
56 protected void execute() {
f0a71840
CZ
57 double xVal = 0;
58
59 xVal = this.gyroController
571fb5c9 60 .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle));
f0a71840 61
571fb5c9
CZ
62 double leftDrive = 0;
63 double rightDrive = 0;
f0a71840
CZ
64 if (direction == Constants.Direction.RIGHT) {
65 leftDrive = xVal;
66 rightDrive = -xVal;
571fb5c9 67 } else if (direction == Constants.Direction.LEFT) {
f0a71840
CZ
68 leftDrive = -xVal;
69 rightDrive = xVal;
70 }
71
72 this.driveTrain.setMotorValues(leftDrive, rightDrive);
d17d868d 73 }
74
d17d868d 75 @Override
76 protected boolean isFinished() {
f0a71840 77 return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
d17d868d 78 }
79
d17d868d 80 @Override
81 protected void end() {
82 }
83
d17d868d 84 @Override
85 protected void interrupted() {
f0a71840 86 end();
d17d868d 87 }
aa160dfd 88}