finish implement driveDistance and TurnForAngle using PID algorithm
[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 public TurnForAngle(double angle, Direction direction, double maxTimeOut) {
32 requires(Robot.getDriveTrain());
33 this.direction = direction;
34 this.maxTimeOut = maxTimeOut;
35 this.target = angle;
36
37 this.gyroP = driveTrain.defaultGyroP;
38 this.gyroI = driveTrain.defaultGyroI;
39 this.gyroD = driveTrain.defaultGyroD;
40
41 this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
42 this.gyroController.setDoneRange(1);
43 this.gyroController.setMinDoneCycles(5);
44 }
45
46 @Override
47 protected void initialize() {
48 this.driveTrain.resetEncoders();
49 this.driveTrain.resetGyro();
50 this.gyroController.setSetPoint(this.target);
51 }
52
53 @Override
54 protected void execute() {
55 double xVal = 0;
56
57 xVal = this.gyroController
58 .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle());
59
60 double leftDrive;
61 double rightDrive;
62 if (direction == Constants.Direction.RIGHT) {
63 leftDrive = xVal;
64 rightDrive = -xVal;
65 } else {
66 leftDrive = -xVal;
67 rightDrive = xVal;
68 }
69
70 this.driveTrain.setMotorValues(leftDrive, rightDrive);
71 }
72
73 @Override
74 protected boolean isFinished() {
75 return timeSinceInitialized() >= maxTimeOut || gyroController.isDone();
76 }
77
78 @Override
79 protected void end() {
80 }
81
82 @Override
83 protected void interrupted() {
84 end();
85 }
86 }