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 | ||
571fb5c9 CZ |
31 | private double zeroAngle; |
32 | ||
f0a71840 | 33 | public TurnForAngle(double angle, Direction direction, double maxTimeOut) { |
d17d868d | 34 | requires(Robot.getDriveTrain()); |
f0a71840 CZ |
35 | this.direction = direction; |
36 | this.maxTimeOut = maxTimeOut; | |
571fb5c9 | 37 | this.target = Math.abs(angle); |
f0a71840 | 38 | |
b70398a7 CZ |
39 | if (angle > 90) { |
40 | this.gyroP = driveTrain.largeTurnP; | |
41 | this.gyroI = driveTrain.largeTurnI; | |
42 | this.gyroD = driveTrain.largeTurnD; | |
43 | } else { | |
44 | this.gyroP = driveTrain.smallTurnP; | |
45 | this.gyroI = driveTrain.smallTurnI; | |
46 | this.gyroD = driveTrain.smallTurnD; | |
47 | } | |
f0a71840 CZ |
48 | |
49 | this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD); | |
50 | this.gyroController.setDoneRange(1); | |
51 | this.gyroController.setMinDoneCycles(5); | |
d17d868d | 52 | } |
53 | ||
d17d868d | 54 | @Override |
55 | protected void initialize() { | |
f0a71840 | 56 | this.driveTrain.resetEncoders(); |
f0a71840 | 57 | this.gyroController.setSetPoint(this.target); |
c726d04a | 58 | this.zeroAngle = driveTrain.getAngle(); |
d17d868d | 59 | } |
60 | ||
d17d868d | 61 | @Override |
62 | protected void execute() { | |
f0a71840 CZ |
63 | double xVal = 0; |
64 | ||
65 | xVal = this.gyroController | |
571fb5c9 | 66 | .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle)); |
f0a71840 | 67 | |
571fb5c9 CZ |
68 | double leftDrive = 0; |
69 | double rightDrive = 0; | |
f0a71840 CZ |
70 | if (direction == Constants.Direction.RIGHT) { |
71 | leftDrive = xVal; | |
72 | rightDrive = -xVal; | |
571fb5c9 | 73 | } else if (direction == Constants.Direction.LEFT) { |
f0a71840 CZ |
74 | leftDrive = -xVal; |
75 | rightDrive = xVal; | |
76 | } | |
77 | ||
78 | this.driveTrain.setMotorValues(leftDrive, rightDrive); | |
d17d868d | 79 | } |
80 | ||
d17d868d | 81 | @Override |
82 | protected boolean isFinished() { | |
f0a71840 | 83 | return timeSinceInitialized() >= maxTimeOut || gyroController.isDone(); |
d17d868d | 84 | } |
85 | ||
d17d868d | 86 | @Override |
87 | protected void end() { | |
88 | } | |
89 | ||
d17d868d | 90 | @Override |
91 | protected void interrupted() { | |
f0a71840 | 92 | end(); |
d17d868d | 93 | } |
aa160dfd | 94 | } |