fix zeroAngle error
[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;
f0a71840 27
571fb5c9
CZ
28 private double zeroAngle;
29
f0a71840 30 public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
d17d868d 31 requires(Robot.getDriveTrain());
f0a71840
CZ
32 this.direction = direction;
33 this.maxTimeOut = maxTimeOut;
571fb5c9 34 this.target = Math.abs(angle);
f0a71840 35
90b435ce 36 this.gyroController = Robot.getDriveTrain().getGyroController();
09ee7387 37
f0a71840
CZ
38 this.gyroController.setDoneRange(1);
39 this.gyroController.setMinDoneCycles(5);
d17d868d 40 }
41
d17d868d 42 @Override
43 protected void initialize() {
f0a71840 44 this.driveTrain.resetEncoders();
f0a71840 45 this.gyroController.setSetPoint(this.target);
c726d04a 46 this.zeroAngle = driveTrain.getAngle();
d17d868d 47 }
48
d17d868d 49 @Override
50 protected void execute() {
f0a71840
CZ
51 double xVal = 0;
52
53 xVal = this.gyroController
571fb5c9 54 .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle));
f0a71840 55
571fb5c9
CZ
56 double leftDrive = 0;
57 double rightDrive = 0;
f0a71840
CZ
58 if (direction == Constants.Direction.RIGHT) {
59 leftDrive = xVal;
60 rightDrive = -xVal;
571fb5c9 61 } else if (direction == Constants.Direction.LEFT) {
f0a71840
CZ
62 leftDrive = -xVal;
63 rightDrive = xVal;
64 }
65
66 this.driveTrain.setMotorValues(leftDrive, rightDrive);
d17d868d 67 }
68
d17d868d 69 @Override
70 protected boolean isFinished() {
f0a71840 71 return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
d17d868d 72 }
73
d17d868d 74 @Override
75 protected void end() {
76 }
77
d17d868d 78 @Override
79 protected void interrupted() {
f0a71840 80 end();
d17d868d 81 }
aa160dfd 82}