fix alot of unnecessary/not used code and init gyroController
[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);
4288a3a4
E
35<<<<<<< HEAD
36=======
37 this.zeroAngle = driveTrain.getAngle();
38>>>>>>> fix alot of unnecessary/not used code and init gyroController
f0a71840 39
90b435ce 40 this.gyroController = Robot.getDriveTrain().getGyroController();
09ee7387 41
f0a71840
CZ
42 this.gyroController.setDoneRange(1);
43 this.gyroController.setMinDoneCycles(5);
d17d868d 44 }
45
d17d868d 46 @Override
47 protected void initialize() {
f0a71840 48 this.driveTrain.resetEncoders();
f0a71840 49 this.gyroController.setSetPoint(this.target);
c726d04a 50 this.zeroAngle = driveTrain.getAngle();
d17d868d 51 }
52
d17d868d 53 @Override
54 protected void execute() {
f0a71840
CZ
55 double xVal = 0;
56
57 xVal = this.gyroController
571fb5c9 58 .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle));
f0a71840 59
571fb5c9
CZ
60 double leftDrive = 0;
61 double rightDrive = 0;
f0a71840
CZ
62 if (direction == Constants.Direction.RIGHT) {
63 leftDrive = xVal;
64 rightDrive = -xVal;
571fb5c9 65 } else if (direction == Constants.Direction.LEFT) {
f0a71840
CZ
66 leftDrive = -xVal;
67 rightDrive = xVal;
68 }
69
70 this.driveTrain.setMotorValues(leftDrive, rightDrive);
d17d868d 71 }
72
d17d868d 73 @Override
74 protected boolean isFinished() {
f0a71840 75 return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
d17d868d 76 }
77
d17d868d 78 @Override
79 protected void end() {
80 }
81
d17d868d 82 @Override
83 protected void interrupted() {
f0a71840 84 end();
d17d868d 85 }
aa160dfd 86}