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