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