code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / TurnForAngle.java
1 package org.usfirst.frc.team3501.robot.commands.driving;
2
3 import org.usfirst.frc.team3501.robot.Constants;
4 import org.usfirst.frc.team3501.robot.Constants.Direction;
5 import org.usfirst.frc.team3501.robot.Robot;
6 import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
7 import org.usfirst.frc.team3501.robot.utils.PIDController;
8
9 import edu.wpi.first.wpilibj.command.Command;
10
11 /**
12 * This command turns the robot for a specified angle in specified direction -
13 * either left or right
14 *
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
18 */
19 public class TurnForAngle extends Command {
20 private DriveTrain driveTrain = Robot.getDriveTrain();
21
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
31 private double zeroAngle;
32
33 public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
34 requires(Robot.getDriveTrain());
35 this.direction = direction;
36 this.maxTimeOut = maxTimeOut;
37 this.target = Math.abs(angle);
38
39 if (angle > 90) {
40 this.gyroP = driveTrain.largeTurnP;
41 this.gyroI = driveTrain.largeTurnI;
42 this.gyroD = driveTrain.largeTurnD;
43 } else {
44 this.gyroP = driveTrain.smallTurnP;
45 this.gyroI = driveTrain.smallTurnI;
46 this.gyroD = driveTrain.smallTurnD;
47 }
48
49 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
50 this.gyroController.setDoneRange(1);
51 this.gyroController.setMinDoneCycles(5);
52 }
53
54 @Override
55 protected void initialize() {
56 this.driveTrain.resetEncoders();
57 this.gyroController.setSetPoint(this.target);
58 this.zeroAngle = driveTrain.getAngle();
59 }
60
61 @Override
62 protected void execute() {
63 double xVal = 0;
64
65 xVal = this.gyroController
66 .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle));
67
68 double leftDrive = 0;
69 double rightDrive = 0;
70 if (direction == Constants.Direction.RIGHT) {
71 leftDrive = xVal;
72 rightDrive = -xVal;
73 } else if (direction == Constants.Direction.LEFT) {
74 leftDrive = -xVal;
75 rightDrive = xVal;
76 }
77
78 this.driveTrain.setMotorValues(leftDrive, rightDrive);
79 }
80
81 @Override
82 protected boolean isFinished() {
83 return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
84 }
85
86 @Override
87 protected void end() {
88 }
89
90 @Override
91 protected void interrupted() {
92 end();
93 }
94 }