Commit | Line | Data |
---|---|---|
aa160dfd ME |
1 | package org.usfirst.frc.team3501.robot.commands.driving; |
2 | ||
f0a71840 | 3 | import org.usfirst.frc.team3501.robot.Constants; |
8af76159 | 4 | import org.usfirst.frc.team3501.robot.Constants.Direction; |
aa160dfd | 5 | import org.usfirst.frc.team3501.robot.Robot; |
f0a71840 CZ |
6 | import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; |
7 | import org.usfirst.frc.team3501.robot.utils.PIDController; | |
aa160dfd ME |
8 | |
9 | import 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 | */ |
19 | public 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; | |
27 | private double gyroP; | |
28 | private double gyroI; | |
29 | private double gyroD; | |
30 | ||
31 | public TurnForAngle(double angle, Direction direction, double maxTimeOut) { | |
d17d868d | 32 | requires(Robot.getDriveTrain()); |
f0a71840 CZ |
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); | |
d17d868d | 44 | } |
45 | ||
d17d868d | 46 | @Override |
47 | protected void initialize() { | |
f0a71840 CZ |
48 | this.driveTrain.resetEncoders(); |
49 | this.driveTrain.resetGyro(); | |
50 | this.gyroController.setSetPoint(this.target); | |
d17d868d | 51 | } |
52 | ||
d17d868d | 53 | @Override |
54 | protected void execute() { | |
f0a71840 CZ |
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); | |
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 | } |