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