| 1 | package org.usfirst.frc.team3501.robot.commands.driving; |
| 2 | |
| 3 | import org.usfirst.frc.team3501.robot.Robot; |
| 4 | import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; |
| 5 | import org.usfirst.frc.team3501.robot.utils.PIDController; |
| 6 | |
| 7 | import edu.wpi.first.wpilibj.Preferences; |
| 8 | import edu.wpi.first.wpilibj.command.Command; |
| 9 | |
| 10 | /** |
| 11 | * This command makes the robot drive a specified distance using encoders on the |
| 12 | * robot and using a feedback loop |
| 13 | * |
| 14 | * parameters: distance the robot will move in inches motorVal: the motor input |
| 15 | * to set the motors to |
| 16 | */ |
| 17 | public class DriveDistance extends Command { |
| 18 | private DriveTrain driveTrain = Robot.getDriveTrain(); |
| 19 | private double maxTimeOut; |
| 20 | private double target; |
| 21 | private double zeroAngle; |
| 22 | private Preferences prefs; |
| 23 | private PIDController driveController; |
| 24 | |
| 25 | private double gyroP; |
| 26 | |
| 27 | public DriveDistance(double distance, double maxTimeOut) { |
| 28 | requires(driveTrain); |
| 29 | this.maxTimeOut = maxTimeOut; |
| 30 | this.target = distance; |
| 31 | this.driveController = driveTrain.getDriveController(); |
| 32 | this.driveController.setDoneRange(0.5); |
| 33 | this.driveController.setMaxOutput(1.0); |
| 34 | this.driveController.setMinDoneCycles(5); |
| 35 | } |
| 36 | |
| 37 | @Override |
| 38 | protected void initialize() { |
| 39 | this.driveTrain.resetEncoders(); |
| 40 | this.driveController.setSetPoint(this.target); |
| 41 | } |
| 42 | |
| 43 | @Override |
| 44 | protected void execute() { |
| 45 | double xVal = gyroP * (driveTrain.getAngle() - zeroAngle); |
| 46 | double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance()); |
| 47 | |
| 48 | double leftDrive = yVal - xVal; |
| 49 | double rightDrive = yVal + xVal; |
| 50 | this.driveTrain.setMotorValues(leftDrive, rightDrive); |
| 51 | } |
| 52 | |
| 53 | @Override |
| 54 | protected boolean isFinished() { |
| 55 | return timeSinceInitialized() >= maxTimeOut |
| 56 | || this.driveController.isDone(); |
| 57 | } |
| 58 | |
| 59 | @Override |
| 60 | protected void end() { |
| 61 | } |
| 62 | |
| 63 | @Override |
| 64 | protected void interrupted() { |
| 65 | end(); |
| 66 | } |
| 67 | } |